38 #ifndef TF2_ROS__BUFFER_SERVER_H_
39 #define TF2_ROS__BUFFER_SERVER_H_
42 #include <tf2/buffer_core_interface.h>
45 #include <geometry_msgs/msg/transform_stamped.hpp>
46 #include <rclcpp/create_timer.hpp>
47 #include <rclcpp/rclcpp.hpp>
48 #include <rclcpp_action/rclcpp_action.hpp>
49 #include <tf2_msgs/action/lookup_transform.hpp>
66 using LookupTransformAction = tf2_msgs::action::LookupTransform;
76 template<
typename NodePtr>
78 const tf2::BufferCoreInterface & buffer,
81 tf2::Duration check_period = tf2::durationFromSec(0.01))
83 logger_(node->get_logger())
85 server_ = rclcpp_action::create_server<LookupTransformAction>(
88 std::bind(&BufferServer::goalCB,
this, std::placeholders::_1, std::placeholders::_2),
89 std::bind(&BufferServer::cancelCB,
this, std::placeholders::_1),
90 std::bind(&BufferServer::acceptedCB,
this, std::placeholders::_1));
92 check_timer_ = rclcpp::create_timer(
93 node, node->get_clock(), check_period,
std::bind(&BufferServer::checkTransforms,
this));
94 RCLCPP_DEBUG(logger_,
"Buffer server started");
101 tf2::TimePoint end_time;
105 rclcpp_action::GoalResponse goalCB(
109 void acceptedCB(GoalHandle gh);
112 rclcpp_action::CancelResponse cancelCB(GoalHandle gh);
115 void checkTransforms();
118 bool canTransform(GoalHandle gh);
121 geometry_msgs::msg::TransformStamped lookupTransform(GoalHandle gh);
123 const tf2::BufferCoreInterface & buffer_;
124 rclcpp::Logger logger_;
125 rclcpp_action::Server<LookupTransformAction>::SharedPtr server_;
128 rclcpp::TimerBase::SharedPtr check_timer_;
133 #endif // TF2_ROS__BUFFER_SERVER_H_