Class TransformListener

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)

Simplified constructor for transform listener.

This constructor will create a new ROS 2 node under the hood. If you already have access to a ROS 2 node and you want to associate the TransformListener to it, then it’s recommended to use one of the other constructors.

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>())

Node constructor.

template<class AllocatorT = std::allocator<void>>
inline TransformListener(tf2::BufferCore &buffer, rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters, rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics, 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>())

Node interface constructor.

virtual TF2_ROS_PUBLIC ~TransformListener()
virtual TF2_ROS_PUBLIC void subscription_callback (tf2_msgs::msg::TFMessage::ConstSharedPtr msg, bool is_static)

Callback function for ros message subscription.