tf2_ros
master
This package contains the ROS bindings for the tf2 library, for both Python and C++.
|
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.
More...
#include <static_transform_broadcaster.h>
Public Member Functions | |
template<class NodeT , class AllocatorT = std::allocator<void>> | |
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 interface constructor. More... | |
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. More... | |
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. More... | |
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.
|
inline |
Node interface constructor.
TF2_ROS_PUBLIC void tf2_ros::StaticTransformBroadcaster::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 tf2_ros::StaticTransformBroadcaster::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.