Class StaticTransformBroadcaster
Defined in File static_transform_broadcaster.hpp
Class Documentation
-
class StaticTransformBroadcaster
This class provides an easy way to publish coordinate frame transform information. It will handle all the messaging and stuffing of messages. And the function prototypes lay out all the necessary data needed for each message.
Public Types
-
using NodeParametersInterface = rclcpp::node_interfaces::NodeParametersInterface
-
using NodeTopicsInterface = rclcpp::node_interfaces::NodeTopicsInterface
-
using RequiredInterfaces = rclcpp::node_interfaces::NodeInterfaces<NodeParametersInterface, NodeTopicsInterface>
Public Functions
-
template<class AllocatorT = std::allocator<void>>
inline StaticTransformBroadcaster(RequiredInterfaces node_interfaces, const rclcpp::QoS &qos = StaticBroadcasterQoS(), const rclcpp::PublisherOptionsWithAllocator<AllocatorT> &options =[]() { rclcpp::PublisherOptionsWithAllocator< AllocatorT > options;options.qos_overriding_options=rclcpp::QosOverridingOptions{ rclcpp::QosPolicyKind::Depth, rclcpp::QosPolicyKind::History, rclcpp::QosPolicyKind::Reliability};return options;}()) NodeInterfaces constructor.
-
template<class NodeT, class AllocatorT = std::allocator<void>, std::enable_if_t<rcpputils::is_pointer<NodeT>::value, bool> = true>
inline StaticTransformBroadcaster(NodeT &&node, const rclcpp::QoS &qos = StaticBroadcasterQoS(), const rclcpp::PublisherOptionsWithAllocator<AllocatorT> &options =[]() { rclcpp::PublisherOptionsWithAllocator< AllocatorT > options;options.qos_overriding_options=rclcpp::QosOverridingOptions{ rclcpp::QosPolicyKind::Depth, rclcpp::QosPolicyKind::History, rclcpp::QosPolicyKind::Reliability};return options;}()) Node constructor.
Node interfaces constructor.
- TF2_ROS_PUBLIC void sendTransform (const geometry_msgs::msg::TransformStamped &transform)
Send a TransformStamped message The stamped data structure includes frame_id, and time, and parent_id already.
- TF2_ROS_PUBLIC void sendTransform (const std::vector< geometry_msgs::msg::TransformStamped > &transforms)
Send a vector of TransformStamped messages The stamped data structure includes frame_id, and time, and parent_id already.
-
using NodeParametersInterface = rclcpp::node_interfaces::NodeParametersInterface