00001 #include <ros/ros.h> 00002 #include <std_msgs/String.h> 00003 #include <pm_fourier/fourier_dist.h> 00004 00005 int main(int argc, char **argv) 00006 { 00007 ros::init(argc, argv, "pm_fourier_dist_server"); 00008 ros::NodeHandle nh("~"); 00009 00010 FourierDistance fdist(nh); 00011 ros::ServiceServer service = nh.advertiseService("compute_dissimilarity", &FourierDistance::dissimilarity, &fdist); 00012 00013 int max_thread; 00014 nh.param<int>("max_thread", max_thread, 2); 00015 00016 ROS_INFO("Ready to work (with %i threads)", max_thread); 00017 /* ros::Publisher pub = global_nh.advertise<std_msgs::String>("node_register", 10, true); */ 00018 00019 /* std_msgs::String msg; */ 00020 /* msg.data = ros::this_node::getName(); */ 00021 /* pub.publish(msg); */ 00022 00023 ros::MultiThreadedSpinner spinner(max_thread); 00024 spinner.spin(); 00025 00026 return 0; 00027 } 00028 00029