Class TransformBroadcaster
Defined in File transform_broadcaster.h
Class Documentation
-
class TransformBroadcaster
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 TransformBroadcaster(NodeT &&node, const rclcpp::QoS &qos = DynamicBroadcasterQoS(), const rclcpp::PublisherOptionsWithAllocator<AllocatorT> &options =[]() { rclcpp::PublisherOptionsWithAllocator< AllocatorT > options;options.qos_overriding_options=rclcpp::QosOverridingOptions{ rclcpp::QosPolicyKind::Depth, rclcpp::QosPolicyKind::Durability, 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 transform ʰTₐ added is from
child_frame_id
,a
toheader.frame_id
,h
. That is, position inchild_frame_id
ᵃp can be transformed to position inheader.frame_id
ʰp such that ʰp = ʰTₐ ᵃp .
- TF2_ROS_PUBLIC void sendTransform (const std::vector< geometry_msgs::msg::TransformStamped > &transforms)
Send a vector of TransformStamped messages.
The transforms ʰTₐ added are from
child_frame_id
,a
toheader.frame_id
,h
. That is, position inchild_frame_id
ᵃp can be transformed to position inheader.frame_id
ʰp such that ʰp = ʰTₐ ᵃp .
-
template<class NodeT, class AllocatorT = std::allocator<void>>