Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adding NodeInterfaces to Buffer #656

Merged
merged 6 commits into from Mar 26, 2024
Merged
Show file tree
Hide file tree
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
45 changes: 41 additions & 4 deletions tf2_ros/include/tf2_ros/buffer.h
Expand Up @@ -36,6 +36,7 @@
#include <memory>
#include <mutex>
#include <string>
#include <utility>
#include <unordered_map>

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

#include "geometry_msgs/msg/transform_stamped.hpp"
#include "tf2_msgs/srv/frame_graph.hpp"
#include "rclcpp/node_interfaces/get_node_base_interface.hpp"
#include "rclcpp/node_interfaces/get_node_services_interface.hpp"
#include "rclcpp/node_interfaces/get_node_logging_interface.hpp"
#include "rclcpp/node_interfaces/node_logging_interface.hpp"
#include "rclcpp/rclcpp.hpp"

namespace tf2_ros
Expand All @@ -69,11 +74,43 @@ class Buffer : public BufferInterface, public AsyncBufferInterface, public tf2::
* \param clock A clock to use for time and sleeping
* \param cache_time How long to keep a history of transforms
* \param node If passed advertise the view_frames service that exposes debugging information from the buffer
* \param qos If passed change the quality of service of the frames_server_ service
*/
TF2_ROS_PUBLIC Buffer(
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

restore TF2_ROS_PUBLIC

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yea I imagine that's the only thing throwing it off

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

So TF2_ROS_PUBLIC is essentially

#define TF2_ROS_EXPORT __declspec(dllexport)

or some similar form of dllexport. Thus, it cannot exist in the scope of a definition of it's application according to the docs. We have to immediately define the constructor for Buffer since it's a template. As for removing the macro, the original CI job has linking errors in getFrames and onTimeJump which are the only two private functions used in the constructor of Buffer. I assume that if we mark those functions as able to link, Buffer shouldn't have problems with anything else

template<typename NodeT = rclcpp::Node::SharedPtr>
Buffer(
rclcpp::Clock::SharedPtr clock,
tf2::Duration cache_time = tf2::Duration(tf2::BUFFER_CORE_DEFAULT_CACHE_TIME),
rclcpp::Node::SharedPtr node = rclcpp::Node::SharedPtr());
NodeT && node = NodeT(),
const rclcpp::QoS & qos = rclcpp::ServicesQoS())
: BufferCore(cache_time), clock_(clock), timer_interface_(nullptr)
{
if (nullptr == clock_) {
throw std::invalid_argument("clock must be a valid instance");
}

auto post_jump_cb = [this](const rcl_time_jump_t & jump_info) {onTimeJump(jump_info);};

rcl_jump_threshold_t jump_threshold;
// Disable forward jump callbacks
jump_threshold.min_forward.nanoseconds = 0;
// Anything backwards is a jump
jump_threshold.min_backward.nanoseconds = -1;
// Callback if the clock changes too
jump_threshold.on_clock_change = true;

jump_handler_ = clock_->create_jump_callback(nullptr, post_jump_cb, jump_threshold);

if (node) {
node_logging_interface_ = rclcpp::node_interfaces::get_node_logging_interface(node);

frames_server_ = rclcpp::create_service<tf2_msgs::srv::FrameGraph>(
rclcpp::node_interfaces::get_node_base_interface(node),
rclcpp::node_interfaces::get_node_services_interface(node),
"tf2_frames", std::bind(
&Buffer::getFrames, this, std::placeholders::_1,
std::placeholders::_2), qos, nullptr);
}
}

/** \brief Get the transform between two frames by frame ID.
* \param target_frame The frame to which data should be transformed
Expand Down Expand Up @@ -293,8 +330,8 @@ class Buffer : public BufferInterface, public AsyncBufferInterface, public tf2::
/// \brief A clock to use for time and sleeping
rclcpp::Clock::SharedPtr clock_;

/// \brief A node to advertise the view_frames service
rclcpp::Node::SharedPtr node_;
/// \brief A node logging interface to access the buffer node's logger
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface_;

/// \brief Interface for creating timers
CreateTimerInterface::SharedPtr timer_interface_;
Expand Down
33 changes: 2 additions & 31 deletions tf2_ros/src/buffer.cpp
Expand Up @@ -42,36 +42,6 @@

namespace tf2_ros
{

Buffer::Buffer(
rclcpp::Clock::SharedPtr clock, tf2::Duration cache_time,
rclcpp::Node::SharedPtr node)
: BufferCore(cache_time), clock_(clock), node_(node), timer_interface_(nullptr)
{
if (nullptr == clock_) {
throw std::invalid_argument("clock must be a valid instance");
}

auto post_jump_cb = [this](const rcl_time_jump_t & jump_info) {onTimeJump(jump_info);};

rcl_jump_threshold_t jump_threshold;
// Disable forward jump callbacks
jump_threshold.min_forward.nanoseconds = 0;
// Anything backwards is a jump
jump_threshold.min_backward.nanoseconds = -1;
// Callback if the clock changes too
jump_threshold.on_clock_change = true;

jump_handler_ = clock_->create_jump_callback(nullptr, post_jump_cb, jump_threshold);

if (node_) {
frames_server_ = node_->create_service<tf2_msgs::srv::FrameGraph>(
"tf2_frames", std::bind(
&Buffer::getFrames, this, std::placeholders::_1,
std::placeholders::_2));
}
}

inline
tf2::Duration
from_rclcpp(const rclcpp::Duration & rclcpp_duration)
Expand Down Expand Up @@ -341,7 +311,8 @@ bool Buffer::checkAndErrorDedicatedThreadPresent(std::string * error_str) const

rclcpp::Logger Buffer::getLogger() const
{
return node_ ? node_->get_logger() : rclcpp::get_logger("tf2_buffer");
return node_logging_interface_ ? node_logging_interface_->get_logger() : rclcpp::get_logger(
"tf2_buffer");
}

} // namespace tf2_ros