Class TransformListener
Defined in File transform_listener.h
Class Documentation
-
class TransformListener
This class provides an easy way to request and receive coordinate frame transform information.
Public Functions
-
explicit TF2_ROS_PUBLIC TransformListener(tf2::BufferCore &buffer, bool spin_thread = true)
Constructor for transform listener.
-
template<class NodeT, class AllocatorT = std::allocator<void>>
inline 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 = detail::get_default_transform_listener_sub_options<AllocatorT>(), const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> &static_options = detail::get_default_transform_listener_static_sub_options<AllocatorT>())
-
virtual TF2_ROS_PUBLIC ~TransformListener()
-
explicit TF2_ROS_PUBLIC TransformListener(tf2::BufferCore &buffer, bool spin_thread = true)