41#include <tf2_msgs/TFMessage.h>
42#include <geometry_msgs/TransformStamped.h>
43#include <realtime_tools/realtime_publisher.h>
51 virtual void init(ros::NodeHandle& root_nh);
52 virtual void sendTransform(
const geometry_msgs::TransformStamped& transform);
53 virtual void sendTransform(
const std::vector<geometry_msgs::TransformStamped>& transforms);
57 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::TFMessage>>
realtime_pub_{};
63 void init(ros::NodeHandle& root_nh)
override;
64 void sendTransform(
const geometry_msgs::TransformStamped& transform)
override;
65 void sendTransform(
const std::vector<geometry_msgs::TransformStamped>& transforms)
override;
68 tf2_msgs::TFMessage net_message_{};
Definition tf_rt_broadcaster.h:61
void sendTransform(const geometry_msgs::TransformStamped &transform) override
Definition tf_rt_broadcaster.cpp:75
void init(ros::NodeHandle &root_nh) override
Definition tf_rt_broadcaster.cpp:70
Definition tf_rt_broadcaster.h:48
TfRtBroadcaster()=default
std::shared_ptr< realtime_tools::RealtimePublisher< tf2_msgs::TFMessage > > realtime_pub_
Definition tf_rt_broadcaster.h:57
ros::NodeHandle node_
Definition tf_rt_broadcaster.h:56
virtual void init(ros::NodeHandle &root_nh)
Definition tf_rt_broadcaster.cpp:44
virtual void sendTransform(const geometry_msgs::TransformStamped &transform)
Definition tf_rt_broadcaster.cpp:49
Definition calibration_queue.h:44