From 662dc12651ca3f4f37b543d66e4c726a69c26984 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Sun, 2 Nov 2025 13:27:53 +0000 Subject: [PATCH 1/2] Use NodeInterfaces for TransformBroadcaster construction --- admittance_controller/test/test_admittance_controller.hpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/admittance_controller/test/test_admittance_controller.hpp b/admittance_controller/test/test_admittance_controller.hpp index 2288f675fd..681e6395e5 100644 --- a/admittance_controller/test/test_admittance_controller.hpp +++ b/admittance_controller/test/test_admittance_controller.hpp @@ -34,6 +34,7 @@ #include "geometry_msgs/msg/transform_stamped.hpp" #include "hardware_interface/loaned_command_interface.hpp" #include "hardware_interface/loaned_state_interface.hpp" +#include "rclcpp/node_interfaces/node_interfaces.hpp" #include "rclcpp/parameter_value.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "semantic_components/force_torque_sensor.hpp" @@ -215,7 +216,10 @@ class AdmittanceControllerTest : public ::testing::Test void broadcast_tfs() { - static tf2_ros::TransformBroadcaster br(test_broadcaster_node_); + static tf2_ros::TransformBroadcaster br( + rclcpp::node_interfaces::NodeInterfaces( + test_broadcaster_node_->get_node_parameters_interface(), + test_broadcaster_node_->get_node_topics_interface())); geometry_msgs::msg::TransformStamped transform_stamped; transform_stamped.header.stamp = test_broadcaster_node_->now(); From 4d6319cf24aab03e6b799a15b048d1f6fa7889de Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Sun, 2 Nov 2025 16:31:03 +0000 Subject: [PATCH 2/2] Use NodeInterfaces only from rclcpp 18.0.0 on --- .../test/test_admittance_controller.hpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/admittance_controller/test/test_admittance_controller.hpp b/admittance_controller/test/test_admittance_controller.hpp index 681e6395e5..44ec164c04 100644 --- a/admittance_controller/test/test_admittance_controller.hpp +++ b/admittance_controller/test/test_admittance_controller.hpp @@ -34,8 +34,11 @@ #include "geometry_msgs/msg/transform_stamped.hpp" #include "hardware_interface/loaned_command_interface.hpp" #include "hardware_interface/loaned_state_interface.hpp" -#include "rclcpp/node_interfaces/node_interfaces.hpp" #include "rclcpp/parameter_value.hpp" +#include "rclcpp/version.h" +#if RCLCPP_VERSION_GTE(18, 0, 0) +#include "rclcpp/node_interfaces/node_interfaces.hpp" +#endif #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "semantic_components/force_torque_sensor.hpp" #include "test_asset_6d_robot_description.hpp" @@ -216,10 +219,15 @@ class AdmittanceControllerTest : public ::testing::Test void broadcast_tfs() { +#if RCLCPP_VERSION_GTE(18, 0, 0) static tf2_ros::TransformBroadcaster br( rclcpp::node_interfaces::NodeInterfaces( test_broadcaster_node_->get_node_parameters_interface(), test_broadcaster_node_->get_node_topics_interface())); +#else + static tf2_ros::TransformBroadcaster br(test_broadcaster_node_); +#endif + geometry_msgs::msg::TransformStamped transform_stamped; transform_stamped.header.stamp = test_broadcaster_node_->now();