This class provides an easy way to request and receive coordinate frame transform information. More...
#include <transform_listener.h>
Public Member Functions | |
| TransformListener (tf2::BufferCore &buffer, bool spin_thread=true) | |
| Constructor for transform listener. | |
| TransformListener (tf2::BufferCore &buffer, const ros::NodeHandle &nh, bool spin_thread=true) | |
| ~TransformListener () | |
Private Member Functions | |
| void | dedicatedListenerThread () |
| void | init () |
| Initialize this transform listener, subscribing, advertising services, etc. | |
| void | initWithThread () |
| void | static_subscription_callback (const ros::MessageEvent< tf2_msgs::TFMessage const > &msg_evt) |
| void | subscription_callback (const ros::MessageEvent< tf2_msgs::TFMessage const > &msg_evt) |
| Callback function for ros message subscriptoin. | |
| void | subscription_callback_impl (const ros::MessageEvent< tf2_msgs::TFMessage const > &msg_evt, bool is_static) |
Private Attributes | |
| tf2::BufferCore & | buffer_ |
| boost::thread * | dedicated_listener_thread_ |
| ros::Time | last_update_ |
| ros::Subscriber | message_subscriber_tf_ |
| ros::Subscriber | message_subscriber_tf_static_ |
| ros::NodeHandle | node_ |
| ros::CallbackQueue | tf_message_callback_queue_ |
| bool | using_dedicated_thread_ |
This class provides an easy way to request and receive coordinate frame transform information.
Definition at line 48 of file transform_listener.h.
| TransformListener::TransformListener | ( | tf2::BufferCore & | buffer, |
| bool | spin_thread = true |
||
| ) |
Constructor for transform listener.
Definition at line 38 of file transform_listener.cpp.
| TransformListener::TransformListener | ( | tf2::BufferCore & | buffer, |
| const ros::NodeHandle & | nh, | ||
| bool | spin_thread = true |
||
| ) |
Definition at line 47 of file transform_listener.cpp.
Definition at line 60 of file transform_listener.cpp.
| void tf2_ros::TransformListener::dedicatedListenerThread | ( | ) | [inline, private] |
Definition at line 78 of file transform_listener.h.
| void TransformListener::init | ( | ) | [private] |
Initialize this transform listener, subscribing, advertising services, etc.
Definition at line 70 of file transform_listener.cpp.
| void TransformListener::initWithThread | ( | ) | [private] |
| void TransformListener::static_subscription_callback | ( | const ros::MessageEvent< tf2_msgs::TFMessage const > & | msg_evt | ) | [private] |
Definition at line 97 of file transform_listener.cpp.
| void TransformListener::subscription_callback | ( | const ros::MessageEvent< tf2_msgs::TFMessage const > & | msg_evt | ) | [private] |
Callback function for ros message subscriptoin.
Definition at line 93 of file transform_listener.cpp.
| void TransformListener::subscription_callback_impl | ( | const ros::MessageEvent< tf2_msgs::TFMessage const > & | msg_evt, |
| bool | is_static | ||
| ) | [private] |
Definition at line 102 of file transform_listener.cpp.
Definition at line 74 of file transform_listener.h.
boost::thread* tf2_ros::TransformListener::dedicated_listener_thread_ [private] |
Definition at line 70 of file transform_listener.h.
Definition at line 76 of file transform_listener.h.
Definition at line 72 of file transform_listener.h.
Definition at line 73 of file transform_listener.h.
Definition at line 71 of file transform_listener.h.
Definition at line 69 of file transform_listener.h.
bool tf2_ros::TransformListener::using_dedicated_thread_ [private] |
Definition at line 75 of file transform_listener.h.