This class provides an easy way to request and receive coordinate frame transform information.
More...
#include <transform_listener.h>
This class provides an easy way to request and receive coordinate frame transform information.
◆ TransformListener() [1/2]
| TF2_ROS_PUBLIC tf2_ros::TransformListener::TransformListener |
( |
tf2::BufferCore & |
buffer, |
|
|
bool |
spin_thread = true |
|
) |
| |
|
explicit |
Constructor for transform listener.
◆ TransformListener() [2/2]
template<class NodeT , class AllocatorT = std::allocator<void>>
| tf2_ros::TransformListener::TransformListener |
( |
tf2::BufferCore & |
buffer, |
|
|
NodeT && |
node, |
|
|
bool |
spin_thread = true, |
|
|
const rclcpp::QoS & |
qos = DynamicListenerQoS(), |
|
|
const rclcpp::QoS & |
static_qos = StaticListenerQoS(), |
|
|
const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > & |
options = rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>() |
|
) |
| |
|
inline |
◆ ~TransformListener()
| virtual TF2_ROS_PUBLIC tf2_ros::TransformListener::~TransformListener |
( |
| ) |
|
|
virtual |
The documentation for this class was generated from the following file: