Skip to content

Commit 0e505aa

Browse files
authored
Adding NodeInterfaces to Buffer (#656)
Signed-off-by: CursedRock17 <[email protected]> Signed-off-by: Lucas Wendland <[email protected]>
1 parent 8752526 commit 0e505aa

File tree

2 files changed

+45
-35
lines changed

2 files changed

+45
-35
lines changed

tf2_ros/include/tf2_ros/buffer.h

Lines changed: 43 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@
3636
#include <memory>
3737
#include <mutex>
3838
#include <string>
39+
#include <utility>
3940
#include <unordered_map>
4041

4142
#include "tf2_ros/async_buffer_interface.h"
@@ -47,6 +48,10 @@
4748

4849
#include "geometry_msgs/msg/transform_stamped.hpp"
4950
#include "tf2_msgs/srv/frame_graph.hpp"
51+
#include "rclcpp/node_interfaces/get_node_base_interface.hpp"
52+
#include "rclcpp/node_interfaces/get_node_services_interface.hpp"
53+
#include "rclcpp/node_interfaces/get_node_logging_interface.hpp"
54+
#include "rclcpp/node_interfaces/node_logging_interface.hpp"
5055
#include "rclcpp/rclcpp.hpp"
5156

5257
namespace tf2_ros
@@ -69,11 +74,43 @@ class Buffer : public BufferInterface, public AsyncBufferInterface, public tf2::
6974
* \param clock A clock to use for time and sleeping
7075
* \param cache_time How long to keep a history of transforms
7176
* \param node If passed advertise the view_frames service that exposes debugging information from the buffer
77+
* \param qos If passed change the quality of service of the frames_server_ service
7278
*/
73-
TF2_ROS_PUBLIC Buffer(
79+
template<typename NodeT = rclcpp::Node::SharedPtr>
80+
Buffer(
7481
rclcpp::Clock::SharedPtr clock,
7582
tf2::Duration cache_time = tf2::Duration(tf2::BUFFER_CORE_DEFAULT_CACHE_TIME),
76-
rclcpp::Node::SharedPtr node = rclcpp::Node::SharedPtr());
83+
NodeT && node = NodeT(),
84+
const rclcpp::QoS & qos = rclcpp::ServicesQoS())
85+
: BufferCore(cache_time), clock_(clock), timer_interface_(nullptr)
86+
{
87+
if (nullptr == clock_) {
88+
throw std::invalid_argument("clock must be a valid instance");
89+
}
90+
91+
auto post_jump_cb = [this](const rcl_time_jump_t & jump_info) {onTimeJump(jump_info);};
92+
93+
rcl_jump_threshold_t jump_threshold;
94+
// Disable forward jump callbacks
95+
jump_threshold.min_forward.nanoseconds = 0;
96+
// Anything backwards is a jump
97+
jump_threshold.min_backward.nanoseconds = -1;
98+
// Callback if the clock changes too
99+
jump_threshold.on_clock_change = true;
100+
101+
jump_handler_ = clock_->create_jump_callback(nullptr, post_jump_cb, jump_threshold);
102+
103+
if (node) {
104+
node_logging_interface_ = rclcpp::node_interfaces::get_node_logging_interface(node);
105+
106+
frames_server_ = rclcpp::create_service<tf2_msgs::srv::FrameGraph>(
107+
rclcpp::node_interfaces::get_node_base_interface(node),
108+
rclcpp::node_interfaces::get_node_services_interface(node),
109+
"tf2_frames", std::bind(
110+
&Buffer::getFrames, this, std::placeholders::_1,
111+
std::placeholders::_2), qos, nullptr);
112+
}
113+
}
77114

78115
/** \brief Get the transform between two frames by frame ID.
79116
* \param target_frame The frame to which data should be transformed
@@ -275,10 +312,12 @@ class Buffer : public BufferInterface, public AsyncBufferInterface, public tf2::
275312
TransformStampedFuture future,
276313
TransformReadyCallback callback);
277314

315+
TF2_ROS_PUBLIC
278316
bool getFrames(
279317
const tf2_msgs::srv::FrameGraph::Request::SharedPtr req,
280318
tf2_msgs::srv::FrameGraph::Response::SharedPtr res);
281319

320+
TF2_ROS_PUBLIC
282321
void onTimeJump(const rcl_time_jump_t & jump);
283322

284323
// conditionally error if dedicated_thread unset.
@@ -293,8 +332,8 @@ class Buffer : public BufferInterface, public AsyncBufferInterface, public tf2::
293332
/// \brief A clock to use for time and sleeping
294333
rclcpp::Clock::SharedPtr clock_;
295334

296-
/// \brief A node to advertise the view_frames service
297-
rclcpp::Node::SharedPtr node_;
335+
/// \brief A node logging interface to access the buffer node's logger
336+
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface_;
298337

299338
/// \brief Interface for creating timers
300339
CreateTimerInterface::SharedPtr timer_interface_;

tf2_ros/src/buffer.cpp

Lines changed: 2 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -42,36 +42,6 @@
4242

4343
namespace tf2_ros
4444
{
45-
46-
Buffer::Buffer(
47-
rclcpp::Clock::SharedPtr clock, tf2::Duration cache_time,
48-
rclcpp::Node::SharedPtr node)
49-
: BufferCore(cache_time), clock_(clock), node_(node), timer_interface_(nullptr)
50-
{
51-
if (nullptr == clock_) {
52-
throw std::invalid_argument("clock must be a valid instance");
53-
}
54-
55-
auto post_jump_cb = [this](const rcl_time_jump_t & jump_info) {onTimeJump(jump_info);};
56-
57-
rcl_jump_threshold_t jump_threshold;
58-
// Disable forward jump callbacks
59-
jump_threshold.min_forward.nanoseconds = 0;
60-
// Anything backwards is a jump
61-
jump_threshold.min_backward.nanoseconds = -1;
62-
// Callback if the clock changes too
63-
jump_threshold.on_clock_change = true;
64-
65-
jump_handler_ = clock_->create_jump_callback(nullptr, post_jump_cb, jump_threshold);
66-
67-
if (node_) {
68-
frames_server_ = node_->create_service<tf2_msgs::srv::FrameGraph>(
69-
"tf2_frames", std::bind(
70-
&Buffer::getFrames, this, std::placeholders::_1,
71-
std::placeholders::_2));
72-
}
73-
}
74-
7545
inline
7646
tf2::Duration
7747
from_rclcpp(const rclcpp::Duration & rclcpp_duration)
@@ -341,7 +311,8 @@ bool Buffer::checkAndErrorDedicatedThreadPresent(std::string * error_str) const
341311

342312
rclcpp::Logger Buffer::getLogger() const
343313
{
344-
return node_ ? node_->get_logger() : rclcpp::get_logger("tf2_buffer");
314+
return node_logging_interface_ ? node_logging_interface_->get_logger() : rclcpp::get_logger(
315+
"tf2_buffer");
345316
}
346317

347318
} // namespace tf2_ros

0 commit comments

Comments
 (0)