Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019 #include <ros/ros.h>
00020
00021 #include <place_matcher_msgs/GetCapability.h>
00022
00023 #include <place_matcher_mcc/jockey.h>
00024
00025 bool callback_getCapability(place_matcher_msgs::GetCapabilityRequest& req, place_matcher_msgs::GetCapabilityResponse& res)
00026 {
00027 res.scale_invariance = place_matcher_msgs::GetCapabilityResponse::TRUE;
00028 res.translation_invariance = place_matcher_msgs::GetCapabilityResponse::TRUE;
00029 res.rotation_invariance = place_matcher_msgs::GetCapabilityResponse::OPTIONAL;
00030 res.provides_dissimilarity = true;
00031 res.provides_pose = false;
00032 return true;
00033 }
00034
00035 int main(int argc, char **argv)
00036 {
00037 int max_thread;
00038 ros::init(argc, argv, "lj_mcc");
00039 ros::NodeHandle nh("~");
00040
00041 nh.param<int>("max_thread", max_thread, 1);
00042
00043
00044 std::string localizing_jockey_server;
00045 nh.param<std::string>("localizing_jockey_server_name",
00046 localizing_jockey_server, ros::this_node::getName() + "_server");
00047
00048 place_matcher_mcc::Jockey jockey(localizing_jockey_server);
00049
00050
00051 if (nh.hasParam("sample_count"))
00052 {
00053 int sample_count;
00054 nh.getParam("sample_count", sample_count);
00055 if (sample_count > 0)
00056 {
00057 jockey.setSampleCount(sample_count);
00058 }
00059 else
00060 {
00061 ROS_WARN_STREAM(nh.getNamespace() <<
00062 "/sample_count must be positive, setting to default (" <<
00063 jockey.getSampleCount() << ")");
00064 }
00065 }
00066
00067
00068 if (nh.hasParam("scale_count"))
00069 {
00070 int scale_count;
00071 nh.getParam("scale_count", scale_count);
00072 if (scale_count > 0)
00073 {
00074 jockey.setScaleCount(scale_count);
00075 }
00076 else
00077 {
00078 ROS_WARN_STREAM(nh.getNamespace() <<
00079 "/scale_count must be positive, setting to default (" <<
00080 jockey.getScaleCount() << ")");
00081 }
00082 }
00083
00084
00085 bool rotation_invariance = jockey.getRotationInvariance();
00086 nh.getParam("rotation_invariance", rotation_invariance);
00087 jockey.setRotationInvariance(rotation_invariance);
00088
00089 ros::ServiceServer get_capability_server = nh.advertiseService("get_capability", callback_getCapability);
00090
00091 ROS_INFO("Ready to work (with %i threads)", max_thread);
00092
00093 ros::MultiThreadedSpinner spinner(max_thread);
00094 spinner.spin();
00095
00096 return 0;
00097 }
00098