int main (int argc, char **argv) { ros::init(argc, argv, "hand_gesture_node"); ros::NodeHandle private_nh_; ROS_INFO(" Launching Hand Gesture Publisher Noide"); string path = ros::package::getPath("qbo_music_player"); path+="/hand_gestures/"; /* * Set ROS parameters */ private_nh_.param("/hand_gesture_node/certainty_threshold", certainty_threshold, 0.26); private_nh_.param("/hand_gesture_node/stabilizer_max", max_stabilizer, 6); private_nh_.param("/hand_gesture_node/stabilizer_threshold", stabilizer_threshold, 5); //Building orbit ROS_INFO("Launching Gesture recognizer..."); ROS_INFO("Certainty threshold: %lg, Stabilizer Threshold: %d, Stabilizer Max: %d", certainty_threshold, stabilizer_threshold, max_stabilizer); orbit = new Orbit(path); //orbit->linear_kernel = true; ROS_INFO("Preparing Gesture Recognizer for BOW with SVN..."); orbit->prepareOrbit(Orbit::BAG_OF_WORDS_SVM); ROS_INFO("Gesture Recognizer ready with threshold %lg!", certainty_threshold); if(orbit->objects_.size()<2) { ROS_ERROR("Insufficient number of hand gestures. Calibrate Hand Gesture with more than 1 hand gesture"); return 1; } /* * Initializing stabilizer values */ for(unsigned int i = 0; i< orbit->objects_.size();i++) { hands.push_back(orbit->objects_[i].name_); stabilizer.push_back(0); } last_hand_received = ros::Time::now(); //Initializing not known value stabilizer.push_back(0); image_sub_=private_nh_.subscribe<sensor_msgs::Image>("/qbo_stereo_selector/object",1,&stereoSelectorCallback); hand_pub = private_nh_.advertise<std_msgs::String>("/hand_gesture_node/hand_gesture", 10); ROS_INFO("Hand Gesture Node Launched!"); ros::spin(); return 0; }