place_matcher_csm_node.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 
00003 #include <place_matcher_msgs/GetCapability.h>
00004 
00005 #include <place_matcher_csm/dissimilarity_getter.h>
00006 
00007 bool callback_getCapability(place_matcher_msgs::GetCapabilityRequest& req, place_matcher_msgs::GetCapabilityResponse& res)
00008 {
00009   res.scale_invariance = place_matcher_msgs::GetCapabilityResponse::FALSE;
00010   res.translation_invariance = place_matcher_msgs::GetCapabilityResponse::TRUE;
00011   res.rotation_invariance = place_matcher_msgs::GetCapabilityResponse::TRUE;
00012   res.provides_dissimilarity = true;
00013   res.provides_pose = true;
00014   return true;
00015 }
00016 
00017 int main(int argc, char *argv[])
00018 {
00019   int max_thread;
00020   ros::init(argc, argv, "polygon_dissimilarity_server_csm");
00021   ros::NodeHandle nh("~");
00022 
00023   nh.param<int>("max_thread", max_thread, 1);
00024 
00025   place_matcher_csm::DissimilarityGetter dissimilarity_getter(nh);
00026 
00027   ros::ServiceServer get_capability_server = nh.advertiseService("get_capability", callback_getCapability);
00028   ros::ServiceServer compute_dissimilarity_server = nh.advertiseService("compute_dissimilarity",
00029       &place_matcher_csm::DissimilarityGetter::getDissimilarity, &dissimilarity_getter);
00030 
00031   ROS_INFO("Ready to work (with %i threads)", max_thread);
00032 
00033   ros::MultiThreadedSpinner spinner(max_thread);
00034   spinner.spin();
00035 
00036   return 0;
00037 }


place_matcher_csm
Author(s): Gaƫl Ecorchard
autogenerated on Sat Jun 8 2019 19:52:59