object_tf_broadcaster_node.cpp
Go to the documentation of this file.
00001 #include <object_msgs_tools/ObjectTFBroadcaster.h>
00002 
00003 /***
00004  * Launches a node which runs the ObjectTFBroadcaster.
00005  *
00006  * \author Jennifer Buehler
00007  * \date March 2016
00008  */
00009 int main(int argc, char**argv){
00010         ros::init(argc, argv, "object_tf_broadcaster");
00011 
00012         ros::NodeHandle priv("~");
00013         ros::NodeHandle pub("");
00014 
00015     // use same namespace which is used by launch file to load ROS params
00016     ros::NodeHandle paramNH("object_tf_broadcaster");   
00017 
00018     std::string REGISTER_OBJECT_SERVICE="/register_object";
00019         paramNH.param<std::string>("register_object_service", REGISTER_OBJECT_SERVICE, REGISTER_OBJECT_SERVICE);
00020 
00021         std::string OBJECT_TOPIC="/gazebo_world/object";
00022         paramNH.param<std::string>("object_topic", OBJECT_TOPIC, OBJECT_TOPIC);
00023         
00024     std::string OBJECT_SERVICE="/gazebo_world/object_info";
00025         paramNH.param<std::string>("object_service", OBJECT_SERVICE, OBJECT_SERVICE);
00026         
00027         int PUBLISH_TF_RATE=10;
00028         paramNH.param<int>("publish_tf_rate", PUBLISH_TF_RATE, PUBLISH_TF_RATE);
00029         
00030     int QUERY_OBJECT_INFO_RATE=1;
00031         paramNH.param<int>("query_object_info_rate", QUERY_OBJECT_INFO_RATE, QUERY_OBJECT_INFO_RATE);
00032 
00033     ROS_INFO_STREAM("Starting ObjectTFBroadcaster with topics: register="<<REGISTER_OBJECT_SERVICE 
00034         <<", object="<<OBJECT_TOPIC<<", object service="<<OBJECT_SERVICE<<" tf rate ="
00035         <<PUBLISH_TF_RATE<<", query info rate: "<<QUERY_OBJECT_INFO_RATE);
00036 
00037     object_msgs_tools::ObjectTFBroadcaster broadcaster(
00038         pub,
00039         REGISTER_OBJECT_SERVICE,
00040         PUBLISH_TF_RATE,
00041         QUERY_OBJECT_INFO_RATE,
00042         OBJECT_TOPIC,
00043         OBJECT_SERVICE);
00044 
00045     // ros::MultiThreadedSpinner spinner(4); // Use 4 threads
00046     // spinner.spin(); // spin() will not return until the node has been shutdown
00047         ros::spin();
00048     ROS_INFO("Exit ObjectTFBroadcater");
00049     return 0;
00050 }


object_msgs_tools
Author(s): Jennifer Buehler
autogenerated on Mon Feb 25 2019 03:45:29