33 #ifndef TF2_ROS__STATIC_TRANSFORM_BROADCASTER_H_
34 #define TF2_ROS__STATIC_TRANSFORM_BROADCASTER_H_
38 #include <rclcpp/rclcpp.hpp>
39 #include <geometry_msgs/msg/transform_stamped.hpp>
40 #include <tf2_msgs/msg/tf_message.hpp>
57 template<
class NodeT,
class AllocatorT = std::allocator<
void>>
61 const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = []() {
62 rclcpp::PublisherOptionsWithAllocator<AllocatorT> options;
63 options.qos_overriding_options = rclcpp::QosOverridingOptions{
64 rclcpp::QosPolicyKind::Depth,
65 rclcpp::QosPolicyKind::History,
66 rclcpp::QosPolicyKind::Reliability};
70 publisher_ = rclcpp::create_publisher<tf2_msgs::msg::TFMessage>(
71 node,
"/tf_static", qos, options);
77 void sendTransform(
const geometry_msgs::msg::TransformStamped & transform);
86 rclcpp::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr publisher_;
87 tf2_msgs::msg::TFMessage net_message_;
92 #endif // TF2_ROS__STATIC_TRANSFORM_BROADCASTER_H_