Class StaticTransformListener

Inheritance Relationships

Base Type

Class Documentation

class StaticTransformListener : public tf2_ros::TransformListener

Convenience class for subscribing to static-only transforms.

While users can achieve the same thing with a normal TransformListener, the number of parameters that must be provided is unwieldy.

Public Types

using NodeBaseInterface = rclcpp::node_interfaces::NodeBaseInterface
using NodeLoggingInterface = rclcpp::node_interfaces::NodeLoggingInterface
using NodeParametersInterface = rclcpp::node_interfaces::NodeParametersInterface
using NodeTopicsInterface = rclcpp::node_interfaces::NodeTopicsInterface
using RequiredInterfaces = rclcpp::node_interfaces::NodeInterfaces<NodeBaseInterface, NodeLoggingInterface, NodeParametersInterface, NodeTopicsInterface>

Public Functions

inline explicit TF2_ROS_PUBLIC StaticTransformListener(tf2::BufferCore &buffer, bool spin_thread = true)

Simplified constructor for a static transform listener.

See also

the simplified TransformListener documentation

template<class AllocatorT = std::allocator<void>>
inline StaticTransformListener(tf2::BufferCore &buffer, RequiredInterfaces node_interfaces, bool spin_thread = true, const rclcpp::QoS &static_qos = StaticListenerQoS(), const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> &static_options = detail::get_default_transform_listener_static_sub_options<AllocatorT>())

NodeInterfaces constructor.

template<class NodeT, class AllocatorT = std::allocator<void>, std::enable_if_t<rcpputils::is_pointer<NodeT>::value, bool> = true>
inline StaticTransformListener(tf2::BufferCore &buffer, NodeT &&node, bool spin_thread = true, const rclcpp::QoS &static_qos = StaticListenerQoS(), const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> &static_options = detail::get_default_transform_listener_static_sub_options<AllocatorT>())

Node constructor.

template<class AllocatorT = std::allocator<void>>
inline StaticTransformListener(tf2::BufferCore &buffer, NodeBaseInterface::SharedPtr node_base, NodeLoggingInterface::SharedPtr node_logging, NodeParametersInterface::SharedPtr node_parameters, NodeTopicsInterface::SharedPtr node_topics, bool spin_thread = true, const rclcpp::QoS &static_qos = StaticListenerQoS(), const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> &static_options = detail::get_default_transform_listener_static_sub_options<AllocatorT>())

Node interface constructor.

inline virtual TF2_ROS_PUBLIC ~StaticTransformListener()