32 #ifndef TF2_ROS__TRANSFORM_LISTENER_H_
33 #define TF2_ROS__TRANSFORM_LISTENER_H_
38 #include "tf2_msgs/msg/tf_message.hpp"
39 #include "rclcpp/rclcpp.hpp"
57 template<
class NodeT,
class AllocatorT = std::allocator<
void>>
59 tf2::BufferCore & buffer,
61 bool spin_thread =
true,
64 const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options =
65 rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>())
68 init(node, spin_thread, qos, static_qos, options);
75 template<
class NodeT,
class AllocatorT = std::allocator<
void>>
79 const rclcpp::QoS & qos,
80 const rclcpp::QoS & static_qos,
81 const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options =
82 rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>())
84 using callback_t =
std::function<void(tf2_msgs::msg::TFMessage::SharedPtr)>;
85 callback_t cb =
std::bind(&TransformListener::subscription_callback,
this, std::placeholders::_1,
false);
86 callback_t static_cb =
std::bind(&TransformListener::subscription_callback,
this, std::placeholders::_1,
true);
88 message_subscription_tf_ = rclcpp::create_subscription<tf2_msgs::msg::TFMessage>(
94 message_subscription_tf_static_ = rclcpp::create_subscription<tf2_msgs::msg::TFMessage>(
102 initThread(node->get_node_base_interface());
107 void initThread(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface);
111 void subscription_callback(tf2_msgs::msg::TFMessage::SharedPtr msg,
bool is_static);
116 thread_ptr dedicated_listener_thread_;
118 rclcpp::Node::SharedPtr optional_default_node_ =
nullptr;
119 rclcpp::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr message_subscription_tf_;
120 rclcpp::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr message_subscription_tf_static_;
121 tf2::BufferCore & buffer_;
122 tf2::TimePoint last_update_;
126 #endif // TF2_ROS__TRANSFORM_LISTENER_H_