Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion test_tf2/test/test_buffer_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ int main(int argc, char ** argv)

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
tf2_ros::Buffer buffer(clock);
tf2_ros::TransformListener tfl(buffer, node, false);
tf2_ros::TransformListener tfl(buffer, *node, false);
std::unique_ptr<tf2_ros::BufferServer> server = std::make_unique<tf2_ros::BufferServer>(
buffer,
node,
Expand Down
54 changes: 18 additions & 36 deletions test_tf2/test/test_message_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,14 +79,12 @@ class Notification
TEST(MessageFilter, noTransforms)
{
auto node = rclcpp::Node::make_shared("tf2_ros_message_filter");
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
node->get_node_base_interface(),
node->get_node_timers_interface());
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(*node);

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
tf2_ros::Buffer buffer(clock);
buffer.setCreateTimerInterface(create_timer_interface);
tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped> filter(buffer, "frame1", 10, node);
tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped> filter(buffer, "frame1", 10, *node);
Notification n(1);
filter.registerCallback(std::bind(&Notification::notify, &n, std::placeholders::_1));

Expand All @@ -102,14 +100,12 @@ TEST(MessageFilter, noTransforms)
TEST(MessageFilter, noTransformsSameFrame)
{
auto node = rclcpp::Node::make_shared("tf2_ros_message_filter");
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
node->get_node_base_interface(),
node->get_node_timers_interface());
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(*node);

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
tf2_ros::Buffer buffer(clock);
buffer.setCreateTimerInterface(create_timer_interface);
tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped> filter(buffer, "frame1", 10, node);
tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped> filter(buffer, "frame1", 10, *node);
Notification n(1);
filter.registerCallback(std::bind(&Notification::notify, &n, std::placeholders::_1));

Expand Down Expand Up @@ -145,14 +141,12 @@ geometry_msgs::msg::TransformStamped createTransform(
TEST(MessageFilter, preexistingTransforms)
{
auto node = rclcpp::Node::make_shared("tf2_ros_message_filter");
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
node->get_node_base_interface(),
node->get_node_timers_interface());
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(*node);

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
tf2_ros::Buffer buffer(clock);
buffer.setCreateTimerInterface(create_timer_interface);
tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped> filter(buffer, "frame1", 10, node);
tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped> filter(buffer, "frame1", 10, *node);
Notification n(1);

filter.registerCallback(std::bind(&Notification::notify, &n, std::placeholders::_1));
Expand All @@ -176,14 +170,12 @@ TEST(MessageFilter, preexistingTransforms)
TEST(MessageFilter, postTransforms)
{
auto node = rclcpp::Node::make_shared("tf2_ros_message_filter");
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
node->get_node_base_interface(),
node->get_node_timers_interface());
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(*node);

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
tf2_ros::Buffer buffer(clock);
buffer.setCreateTimerInterface(create_timer_interface);
tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped> filter(buffer, "frame1", 10, node);
tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped> filter(buffer, "frame1", 10, *node);
Notification n(1);

filter.registerCallback(std::bind(&Notification::notify, &n, std::placeholders::_1));
Expand Down Expand Up @@ -212,9 +204,7 @@ TEST(MessageFilter, concurrentTransforms)
const int messages = 30;
const int buffer_size = messages;
auto node = rclcpp::Node::make_shared("tf2_ros_message_filter");
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
node->get_node_base_interface(),
node->get_node_timers_interface());
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(*node);

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);

Expand All @@ -229,7 +219,7 @@ TEST(MessageFilter, concurrentTransforms)
for (int i = 0; i < 50; i++) {
buffer.setCreateTimerInterface(create_timer_interface);
tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped> filter(buffer, "frame1", buffer_size,
node);
*node);
Notification n(1);
filter.registerCallback(std::bind(&Notification::notify, &n, std::placeholders::_1));

Expand Down Expand Up @@ -294,14 +284,12 @@ TEST(MessageFilter, concurrentTransforms)
TEST(MessageFilter, setTargetFrame)
{
auto node = rclcpp::Node::make_shared("tf2_ros_message_filter");
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
node->get_node_base_interface(),
node->get_node_timers_interface());
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(*node);

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
tf2_ros::Buffer buffer(clock);
buffer.setCreateTimerInterface(create_timer_interface);
tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped> filter(buffer, "frame1", 10, node);
tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped> filter(buffer, "frame1", 10, *node);
Notification n(1);
filter.registerCallback(std::bind(&Notification::notify, &n, std::placeholders::_1));
filter.setTargetFrame("frame1000");
Expand All @@ -325,14 +313,12 @@ TEST(MessageFilter, setTargetFrame)
TEST(MessageFilter, multipleTargetFrames)
{
auto node = rclcpp::Node::make_shared("tf2_ros_message_filter");
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
node->get_node_base_interface(),
node->get_node_timers_interface());
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(*node);

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
tf2_ros::Buffer buffer(clock);
buffer.setCreateTimerInterface(create_timer_interface);
tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped> filter(buffer, "", 10, node);
tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped> filter(buffer, "", 10, *node);
Notification n(1);
filter.registerCallback(std::bind(&Notification::notify, &n, std::placeholders::_1));

Expand Down Expand Up @@ -366,14 +352,12 @@ TEST(MessageFilter, multipleTargetFrames)
TEST(MessageFilter, tolerance)
{
auto node = rclcpp::Node::make_shared("tf2_ros_message_filter");
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
node->get_node_base_interface(),
node->get_node_timers_interface());
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(*node);

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
tf2_ros::Buffer buffer(clock);
buffer.setCreateTimerInterface(create_timer_interface);
tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped> filter(buffer, "frame1", 10, node);
tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped> filter(buffer, "frame1", 10, *node);
Notification n(1);
filter.registerCallback(std::bind(&Notification::notify, &n, std::placeholders::_1));

Expand Down Expand Up @@ -497,14 +481,12 @@ TEST(MessageFilter, tolerance)
TEST(MessageFilter, checkStampPrecisionLoss)
{
auto node = rclcpp::Node::make_shared("tf2_ros_message_filter");
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
node->get_node_base_interface(),
node->get_node_timers_interface());
auto create_timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(*node);

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
tf2_ros::Buffer buffer(clock);
buffer.setCreateTimerInterface(create_timer_interface);
tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped> filter(buffer, "frame1", 10, node);
tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped> filter(buffer, "frame1", 10, *node);
Notification n(1);
filter.registerCallback(std::bind(&Notification::notify, &n, std::placeholders::_1));
filter.setTargetFrame("frame1");
Expand Down
10 changes: 5 additions & 5 deletions test_tf2/test/test_static_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ TEST(StaticTransformPublisher, a_b_different_times)

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
tf2_ros::Buffer mB(clock);
tf2_ros::TransformListener tfl(mB, node, false);
tf2_ros::TransformListener tfl(mB, *node, false);

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);
Expand Down Expand Up @@ -89,7 +89,7 @@ TEST(StaticTransformPublisher, a_c_different_times)

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
tf2_ros::Buffer mB(clock);
tf2_ros::TransformListener tfl(mB, node, false);
tf2_ros::TransformListener tfl(mB, *node, false);

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);
Expand Down Expand Up @@ -123,7 +123,7 @@ TEST(StaticTransformPublisher, a_d_different_times)

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
tf2_ros::Buffer mB(clock);
tf2_ros::TransformListener tfl(mB, node, false);
tf2_ros::TransformListener tfl(mB, *node, false);

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);
Expand Down Expand Up @@ -174,7 +174,7 @@ TEST(StaticTransformPublisher, multiple_parent_test)

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
tf2_ros::Buffer mB(clock);
tf2_ros::TransformListener tfl(mB, node, false);
tf2_ros::TransformListener tfl(mB, *node, false);

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);
Expand All @@ -194,7 +194,7 @@ TEST(StaticTransformPublisher, multiple_parent_test)
}
}

tf2_ros::StaticTransformBroadcaster stb(node);
tf2_ros::StaticTransformBroadcaster stb(*node);
geometry_msgs::msg::TransformStamped ts;
ts.transform.rotation.w = 1;
ts.header.frame_id = "c";
Expand Down
3 changes: 3 additions & 0 deletions tf2_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ find_package(rcl_interfaces REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(rcpputils REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_msgs REQUIRED)

Expand All @@ -40,6 +41,7 @@ target_link_libraries(${PROJECT_NAME} PUBLIC
message_filters::message_filters
rclcpp::rclcpp
rclcpp_action::rclcpp_action
rcpputils::rcpputils
tf2::tf2
${tf2_msgs_TARGETS})

Expand Down Expand Up @@ -236,6 +238,7 @@ ament_export_dependencies(
message_filters
rclcpp
rclcpp_action
rcpputils
tf2
tf2_msgs
)
Expand Down
60 changes: 31 additions & 29 deletions tf2_ros/include/tf2_ros/buffer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
#include <memory>
#include <mutex>
#include <string>
#include <type_traits>
#include <utility>
#include <unordered_map>

Expand All @@ -51,7 +52,10 @@
#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_base_interface.hpp"
#include "rclcpp/node_interfaces/node_services_interface.hpp"
#include "rclcpp/node_interfaces/node_logging_interface.hpp"
#include "rclcpp/node_interfaces/node_interfaces.hpp"
#include "rclcpp/rclcpp.hpp"

namespace tf2_ros
Expand All @@ -70,46 +74,41 @@ class Buffer : public BufferInterface, public AsyncBufferInterface, public tf2::
using tf2::BufferCore::canTransform;
using SharedPtr = std::shared_ptr<tf2_ros::Buffer>;

using NodeBaseInterface = rclcpp::node_interfaces::NodeBaseInterface;
using NodeLoggingInterface = rclcpp::node_interfaces::NodeLoggingInterface;
using NodeServicesInterface = rclcpp::node_interfaces::NodeServicesInterface;
using RequiredInterfaces = rclcpp::node_interfaces::NodeInterfaces<NodeBaseInterface,
NodeLoggingInterface, NodeServicesInterface>;

/** \brief Constructor for a Buffer object
* \param clock A clock to use for time and sleeping
* \param cache_time How long to keep a history of transforms
* \param interfaces If passed advertise the view_frames service that exposes debugging information from the buffer, based on a set of node interfaces
* \param qos If passed change the quality of service of the frames_server_ service
*/
TF2_ROS_PUBLIC
Buffer(
rclcpp::Clock::SharedPtr clock,
tf2::Duration cache_time = tf2::Duration(tf2::BUFFER_CORE_DEFAULT_CACHE_TIME),
RequiredInterfaces node_interfaces = RequiredInterfaces(),
const rclcpp::QoS & qos = rclcpp::ServicesQoS());

/** \brief Constructor for a Buffer object
* \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
*/
template<typename NodeT = rclcpp::Node::SharedPtr>
template<class NodeT = rclcpp::Node::SharedPtr, class AllocatorT = std::allocator<void>,
std::enable_if_t<rcpputils::is_pointer<NodeT>::value, bool> = true>
Comment thread
CursedRock17 marked this conversation as resolved.
[[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of NoteT")]]
Buffer(
rclcpp::Clock::SharedPtr clock,
tf2::Duration cache_time = tf2::Duration(tf2::BUFFER_CORE_DEFAULT_CACHE_TIME),
NodeT && node = NodeT(),
const rclcpp::QoS & qos = rclcpp::ServicesQoS())
: BufferCore(cache_time), clock_(clock), timer_interface_(nullptr)
: Buffer(clock, cache_time, *node, qos)
{
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.
Expand Down Expand Up @@ -332,8 +331,11 @@ class Buffer : public BufferInterface, public AsyncBufferInterface, public tf2::
/// \brief A clock to use for time and sleeping
rclcpp::Clock::SharedPtr clock_;

/// \brief A set of interface to access the buffer's node
RequiredInterfaces node_interfaces_;

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

/// \brief Interface for creating timers
CreateTimerInterface::SharedPtr timer_interface_;
Expand Down
21 changes: 17 additions & 4 deletions tf2_ros/include/tf2_ros/create_timer_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,9 @@
#include "tf2/time.hpp"

#include "rclcpp/rclcpp.hpp"
#include "rclcpp/node_interfaces/node_interfaces.hpp"
#include "rclcpp/node_interfaces/get_node_base_interface.hpp"
#include "rclcpp/node_interfaces/get_node_timers_interface.hpp"

namespace tf2_ros
{
Expand All @@ -50,10 +53,21 @@ namespace tf2_ros
class CreateTimerROS : public CreateTimerInterface
{
public:
using NodeBaseInterface = rclcpp::node_interfaces::NodeBaseInterface;
using NodeTimersInterface = rclcpp::node_interfaces::NodeTimersInterface;
using RequiredInterfaces = rclcpp::node_interfaces::NodeInterfaces<NodeBaseInterface,
NodeTimersInterface>;

TF2_ROS_PUBLIC
CreateTimerROS(
RequiredInterfaces node_interfaces,
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr);

[[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of multiple interfaces")]]
TF2_ROS_PUBLIC
CreateTimerROS(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers,
NodeBaseInterface::SharedPtr node_base,
NodeTimersInterface::SharedPtr node_timers,
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr);

virtual ~CreateTimerROS() = default;
Expand Down Expand Up @@ -119,8 +133,7 @@ class CreateTimerROS : public CreateTimerInterface
const TimerHandle & timer_handle,
TimerCallbackType callback);

rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
RequiredInterfaces node_interfaces_;
TimerHandle next_timer_handle_index_;
std::unordered_map<TimerHandle, rclcpp::TimerBase::SharedPtr> timers_map_;
std::mutex timers_map_mutex_;
Expand Down
Loading