| tf2_ros
    master
    This package contains the ROS bindings for the tf2 library, for both Python and C++. | 
 
 
 
Go to the documentation of this file.
   33 #ifndef TF2_ROS_TRANSFORMBROADCASTER_H 
   34 #define TF2_ROS_TRANSFORMBROADCASTER_H 
   36 #include "rclcpp/rclcpp.hpp" 
   37 #include "geometry_msgs/msg/transform_stamped.hpp" 
   38 #include "tf2_msgs/msg/tf_message.hpp" 
   52   template<
class NodeT, 
class AllocatorT = std::allocator<
void>>
 
   56     const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options =
 
   57       rclcpp::PublisherOptionsWithAllocator<AllocatorT>())
 
   59     publisher_ = rclcpp::create_publisher<tf2_msgs::msg::TFMessage>(
 
   60       node, 
"/tf", qos, options);
 
   74   void sendTransform(
const geometry_msgs::msg::TransformStamped & transform);
 
   82   rclcpp::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr publisher_;
 
   88 #endif //TF_TRANSFORMBROADCASTER_H 
  
Definition: async_buffer_interface.h:41
#define TF2_ROS_PUBLIC
Definition: visibility_control.h:58