33 #ifndef TF2_ROS_STATICTRANSFORMBROADCASTER_H
34 #define TF2_ROS_STATICTRANSFORMBROADCASTER_H
38 #include "rclcpp/rclcpp.hpp"
39 #include "geometry_msgs/msg/transform_stamped.hpp"
40 #include "tf2_msgs/msg/tf_message.hpp"
54 template<
class NodeT,
class AllocatorT = std::allocator<
void>>
58 const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options =
59 rclcpp::PublisherOptionsWithAllocator<AllocatorT>())
61 publisher_ = rclcpp::create_publisher<tf2_msgs::msg::TFMessage>(
62 node,
"/tf_static", qos, options);
68 void sendTransform(
const geometry_msgs::msg::TransformStamped & transform);
77 rclcpp::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr publisher_;
78 tf2_msgs::msg::TFMessage net_message_;
84 #endif //TF_STATICTRANSFORMBROADCASTER_H