#include <rocon_tf_reconstructor.h>
Public Member Functions | |
| RoconTFReconstructor () | |
| RoconTFReconstructor (ros::NodeHandle &n) | |
| void | spin () |
| ~RoconTFReconstructor () | |
Protected Member Functions | |
| void | getParams () |
| void | init () |
| void | processClientLists (const concert_msgs::ConcertClients::ConstPtr msg) |
| void | publishClientTF (std::string client_name, geometry_msgs::PoseStamped pose_stamped) |
| void | setSubscriber () |
Private Attributes | |
| std::vector< std::string > | clients |
| ros::NodeHandle | nh |
| std::string | sub_client_list_topic |
| ros::Subscriber | sub_clientlist |
| std::map< std::string, RoconPoseClient * > | sub_clients_pose |
| std::string | sub_robotpose_topic |
| tf::TransformBroadcaster | tf_broadcaster |
Definition at line 49 of file rocon_tf_reconstructor.h.
Definition at line 5 of file rocon_tf_reconstructor.cpp.
Definition at line 10 of file rocon_tf_reconstructor.cpp.
Definition at line 17 of file rocon_tf_reconstructor.cpp.
| void rocon::RoconTFReconstructor::getParams | ( | ) | [protected] |
Definition at line 27 of file rocon_tf_reconstructor.cpp.
| void rocon::RoconTFReconstructor::init | ( | ) | [protected] |
Definition at line 21 of file rocon_tf_reconstructor.cpp.
| void rocon::RoconTFReconstructor::processClientLists | ( | const concert_msgs::ConcertClients::ConstPtr | msg | ) | [protected] |
Definition at line 39 of file rocon_tf_reconstructor.cpp.
| void rocon::RoconTFReconstructor::publishClientTF | ( | std::string | client_name, |
| geometry_msgs::PoseStamped | pose_stamped | ||
| ) | [protected] |
Definition at line 75 of file rocon_tf_reconstructor.cpp.
| void rocon::RoconTFReconstructor::setSubscriber | ( | ) | [protected] |
Definition at line 34 of file rocon_tf_reconstructor.cpp.
| void rocon::RoconTFReconstructor::spin | ( | ) |
Definition at line 90 of file rocon_tf_reconstructor.cpp.
std::vector<std::string> rocon::RoconTFReconstructor::clients [private] |
Definition at line 70 of file rocon_tf_reconstructor.h.
Definition at line 65 of file rocon_tf_reconstructor.h.
std::string rocon::RoconTFReconstructor::sub_client_list_topic [private] |
Definition at line 73 of file rocon_tf_reconstructor.h.
Definition at line 68 of file rocon_tf_reconstructor.h.
std::map<std::string,RoconPoseClient*> rocon::RoconTFReconstructor::sub_clients_pose [private] |
Definition at line 71 of file rocon_tf_reconstructor.h.
std::string rocon::RoconTFReconstructor::sub_robotpose_topic [private] |
Definition at line 74 of file rocon_tf_reconstructor.h.
Definition at line 67 of file rocon_tf_reconstructor.h.