33 #ifndef TF2_ROS__TRANSFORM_BROADCASTER_H_
34 #define TF2_ROS__TRANSFORM_BROADCASTER_H_
38 #include <rclcpp/rclcpp.hpp>
39 #include <geometry_msgs/msg/transform_stamped.hpp>
40 #include <tf2_msgs/msg/tf_message.hpp>
58 template<
class NodeT,
class AllocatorT = std::allocator<
void>>
62 const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = []() {
63 rclcpp::PublisherOptionsWithAllocator<AllocatorT> options;
64 options.qos_overriding_options = rclcpp::QosOverridingOptions{
65 rclcpp::QosPolicyKind::Depth,
66 rclcpp::QosPolicyKind::Durability,
67 rclcpp::QosPolicyKind::History,
68 rclcpp::QosPolicyKind::Reliability};
72 publisher_ = rclcpp::create_publisher<tf2_msgs::msg::TFMessage>(
73 node,
"/tf", qos, options);
84 void sendTransform(
const geometry_msgs::msg::TransformStamped & transform);
96 rclcpp::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr publisher_;
101 #endif // TF2_ROS__TRANSFORM_BROADCASTER_H_