Class StaticTransformBroadcaster
Defined in File static_transform_broadcaster.h
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 Functions
-
template<class NodeT, class AllocatorT = std::allocator<void>>
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};options.use_intra_process_comm=rclcpp::IntraProcessSetting::Disable;return options;}()
) Node interface 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.
-
template<class NodeT, class AllocatorT = std::allocator<void>>