From fc7cfa086e5b60a698c76aa81df096bf668b4b99 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Mon, 29 Sep 2025 11:53:41 +0000 Subject: [PATCH 1/5] Cleanup deprecations --- .../test/test_force_torque_sensor.cpp | 76 +++++++++---------- controller_interface/test/test_gps_sensor.cpp | 65 +++++++++------- controller_interface/test/test_imu_sensor.cpp | 40 +++++----- .../test/test_led_rgb_device.cpp | 15 ++-- .../test/test_pose_sensor.cpp | 28 +++---- ...t_semantic_component_command_interface.cpp | 15 ++-- .../test_semantic_component_interface.cpp | 9 ++- .../include/hardware_interface/handle.hpp | 17 ----- .../hardware_interface/hardware_component.hpp | 13 ---- .../hardware_component_interface.hpp | 54 ++----------- .../loaned_command_interface.hpp | 28 ------- .../loaned_state_interface.hpp | 28 ------- .../hardware_interface/resource_manager.hpp | 72 ------------------ hardware_interface/src/hardware_component.cpp | 21 ----- hardware_interface/src/resource_manager.cpp | 33 -------- .../test/test_resource_manager.cpp | 26 +------ 16 files changed, 147 insertions(+), 393 deletions(-) diff --git a/controller_interface/test/test_force_torque_sensor.cpp b/controller_interface/test/test_force_torque_sensor.cpp index f1087a0758..315c04999d 100644 --- a/controller_interface/test/test_force_torque_sensor.cpp +++ b/controller_interface/test/test_force_torque_sensor.cpp @@ -48,20 +48,20 @@ TEST_F(ForceTorqueSensorTest, validate_all_with_default_names) std::vector interface_names = force_torque_sensor_->get_state_interface_names(); // assign values to force - hardware_interface::StateInterface force_x{ - sensor_name_, fts_interface_names_[0], &force_values_[0]}; - hardware_interface::StateInterface force_y{ - sensor_name_, fts_interface_names_[1], &force_values_[1]}; - hardware_interface::StateInterface force_z{ - sensor_name_, fts_interface_names_[2], &force_values_[2]}; + auto force_x = std::make_shared( + sensor_name_, fts_interface_names_[0], &force_values_[0]); + auto force_y = std::make_shared( + sensor_name_, fts_interface_names_[1], &force_values_[1]); + auto force_z = std::make_shared( + sensor_name_, fts_interface_names_[2], &force_values_[2]); // assign values to torque - hardware_interface::StateInterface torque_x{ - sensor_name_, fts_interface_names_[3], &torque_values_[0]}; - hardware_interface::StateInterface torque_y{ - sensor_name_, fts_interface_names_[4], &torque_values_[1]}; - hardware_interface::StateInterface torque_z{ - sensor_name_, fts_interface_names_[5], &torque_values_[2]}; + auto torque_x = std::make_shared( + sensor_name_, fts_interface_names_[3], &torque_values_[0]); + auto torque_y = std::make_shared( + sensor_name_, fts_interface_names_[4], &torque_values_[1]); + auto torque_z = std::make_shared( + sensor_name_, fts_interface_names_[5], &torque_values_[2]); // create local state interface vector std::vector temp_state_interfaces; @@ -132,16 +132,16 @@ TEST_F(ForceTorqueSensorTest, validate_all_with_custom_names) std::vector interface_names = force_torque_sensor_->get_state_interface_names(); // assign values to force.x and force.z - hardware_interface::StateInterface force_x{ - sensor_name_, fts_interface_names_[0], &force_values_[0]}; - hardware_interface::StateInterface force_z{ - sensor_name_, fts_interface_names_[2], &force_values_[2]}; + auto force_x = std::make_shared( + sensor_name_, fts_interface_names_[0], &force_values_[0]); + auto force_z = std::make_shared( + sensor_name_, fts_interface_names_[2], &force_values_[2]); // assign values to torque.y and torque.z - hardware_interface::StateInterface torque_y{ - sensor_name_, fts_interface_names_[4], &torque_values_[1]}; - hardware_interface::StateInterface torque_z{ - sensor_name_, fts_interface_names_[5], &torque_values_[2]}; + auto torque_y = std::make_shared( + sensor_name_, fts_interface_names_[4], &torque_values_[1]); + auto torque_z = std::make_shared( + sensor_name_, fts_interface_names_[5], &torque_values_[2]); // create local state interface vector std::vector temp_state_interfaces; @@ -214,31 +214,31 @@ TEST_F(ForceTorqueSensorTest, validate_all_custom_names) ASSERT_EQ(force_torque_sensor_->interface_names_[5], sensor_name_ + "/" + "torque.z"); // assign values to force - hardware_interface::StateInterface force_x{ - sensor_name_, fts_interface_names_[0], &force_values_[0]}; - hardware_interface::StateInterface force_y{ - sensor_name_, fts_interface_names_[1], &force_values_[1]}; - hardware_interface::StateInterface force_z{ - sensor_name_, fts_interface_names_[2], &force_values_[2]}; + auto force_x = std::make_shared( + sensor_name_, fts_interface_names_[0], &force_values_[0]); + auto force_y = std::make_shared( + sensor_name_, fts_interface_names_[1], &force_values_[1]); + auto force_z = std::make_shared( + sensor_name_, fts_interface_names_[2], &force_values_[2]); // assign values to torque - hardware_interface::StateInterface torque_x{ - sensor_name_, fts_interface_names_[3], &torque_values_[0]}; - hardware_interface::StateInterface torque_y{ - sensor_name_, fts_interface_names_[4], &torque_values_[1]}; - hardware_interface::StateInterface torque_z{ - sensor_name_, fts_interface_names_[5], &torque_values_[2]}; + auto torque_x = std::make_shared( + sensor_name_, fts_interface_names_[3], &torque_values_[0]); + auto torque_y = std::make_shared( + sensor_name_, fts_interface_names_[4], &torque_values_[1]); + auto torque_z = std::make_shared( + sensor_name_, fts_interface_names_[5], &torque_values_[2]); // create local state interface vector std::vector temp_state_interfaces; // insert the interfaces in jumbled sequence - temp_state_interfaces.emplace_back(torque_y); - temp_state_interfaces.emplace_back(force_z); - temp_state_interfaces.emplace_back(force_x); - temp_state_interfaces.emplace_back(torque_z); - temp_state_interfaces.emplace_back(torque_x); - temp_state_interfaces.emplace_back(force_y); + temp_state_interfaces.emplace_back(torque_y, nullptr); + temp_state_interfaces.emplace_back(force_z, nullptr); + temp_state_interfaces.emplace_back(force_x, nullptr); + temp_state_interfaces.emplace_back(torque_z, nullptr); + temp_state_interfaces.emplace_back(torque_x, nullptr); + temp_state_interfaces.emplace_back(force_y, nullptr); // now call the function to make them in order like interface_names force_torque_sensor_->assign_loaned_state_interfaces(temp_state_interfaces); diff --git a/controller_interface/test/test_gps_sensor.cpp b/controller_interface/test/test_gps_sensor.cpp index 5358692e3b..e2cd748127 100644 --- a/controller_interface/test/test_gps_sensor.cpp +++ b/controller_interface/test/test_gps_sensor.cpp @@ -46,16 +46,21 @@ struct GPSSensorTest : public testing::Test gps_sensor_name}; std::vector full_interface_names; - hardware_interface::StateInterface gps_state{ - gps_sensor_name, gps_interface_names.at(0), &gps_states.at(0)}; - hardware_interface::StateInterface gps_service{ - gps_sensor_name, gps_interface_names.at(1), &gps_states.at(1)}; - hardware_interface::StateInterface latitude{ - gps_sensor_name, gps_interface_names.at(2), &gps_states.at(2)}; - hardware_interface::StateInterface longitude{ - gps_sensor_name, gps_interface_names.at(3), &gps_states.at(3)}; - hardware_interface::StateInterface altitude{ - gps_sensor_name, gps_interface_names.at(4), &gps_states.at(4)}; + hardware_interface::StateInterface::SharedPtr gps_state = + std::make_shared( + gps_sensor_name, gps_interface_names.at(0), &gps_states.at(0)); + hardware_interface::StateInterface::SharedPtr gps_service = + std::make_shared( + gps_sensor_name, gps_interface_names.at(1), &gps_states.at(1)); + hardware_interface::StateInterface::SharedPtr latitude = + std::make_shared( + gps_sensor_name, gps_interface_names.at(2), &gps_states.at(2)); + hardware_interface::StateInterface::SharedPtr longitude = + std::make_shared( + gps_sensor_name, gps_interface_names.at(3), &gps_states.at(3)); + hardware_interface::StateInterface::SharedPtr altitude = + std::make_shared( + gps_sensor_name, gps_interface_names.at(4), &gps_states.at(4)); std::vector state_interface; }; @@ -144,22 +149,30 @@ struct GPSSensorWithCovarianceTest : public testing::Test gps_sensor_name}; std::vector full_interface_names; - hardware_interface::StateInterface gps_state{ - gps_sensor_name, gps_interface_names.at(0), &gps_states.at(0)}; - hardware_interface::StateInterface gps_service{ - gps_sensor_name, gps_interface_names.at(1), &gps_states.at(1)}; - hardware_interface::StateInterface latitude{ - gps_sensor_name, gps_interface_names.at(2), &gps_states.at(2)}; - hardware_interface::StateInterface longitude{ - gps_sensor_name, gps_interface_names.at(3), &gps_states.at(3)}; - hardware_interface::StateInterface altitude{ - gps_sensor_name, gps_interface_names.at(4), &gps_states.at(4)}; - hardware_interface::StateInterface latitude_covariance{ - gps_sensor_name, gps_interface_names.at(5), &gps_states.at(5)}; - hardware_interface::StateInterface longitude_covariance{ - gps_sensor_name, gps_interface_names.at(6), &gps_states.at(6)}; - hardware_interface::StateInterface altitude_covariance{ - gps_sensor_name, gps_interface_names.at(7), &gps_states.at(7)}; + hardware_interface::StateInterface::SharedPtr gps_state = + std::make_shared( + gps_sensor_name, gps_interface_names.at(0), &gps_states.at(0)); + hardware_interface::StateInterface::SharedPtr gps_service = + std::make_shared( + gps_sensor_name, gps_interface_names.at(1), &gps_states.at(1)); + hardware_interface::StateInterface::SharedPtr latitude = + std::make_shared( + gps_sensor_name, gps_interface_names.at(2), &gps_states.at(2)); + hardware_interface::StateInterface::SharedPtr longitude = + std::make_shared( + gps_sensor_name, gps_interface_names.at(3), &gps_states.at(3)); + hardware_interface::StateInterface::SharedPtr altitude = + std::make_shared( + gps_sensor_name, gps_interface_names.at(4), &gps_states.at(4)); + hardware_interface::StateInterface::SharedPtr latitude_covariance = + std::make_shared( + gps_sensor_name, gps_interface_names.at(5), &gps_states.at(5)); + hardware_interface::StateInterface::SharedPtr longitude_covariance = + std::make_shared( + gps_sensor_name, gps_interface_names.at(6), &gps_states.at(6)); + hardware_interface::StateInterface::SharedPtr altitude_covariance = + std::make_shared( + gps_sensor_name, gps_interface_names.at(7), &gps_states.at(7)); std::vector state_interface; }; diff --git a/controller_interface/test/test_imu_sensor.cpp b/controller_interface/test/test_imu_sensor.cpp index f21a5a37ff..e6f8de44e5 100644 --- a/controller_interface/test/test_imu_sensor.cpp +++ b/controller_interface/test/test_imu_sensor.cpp @@ -47,30 +47,30 @@ TEST_F(IMUSensorTest, validate_all) std::vector interface_names = imu_sensor_->get_state_interface_names(); // assign values to orientation - hardware_interface::StateInterface orientation_x{ - sensor_name_, imu_interface_names_[0], &orientation_values_[0]}; - hardware_interface::StateInterface orientation_y{ - sensor_name_, imu_interface_names_[1], &orientation_values_[1]}; - hardware_interface::StateInterface orientation_z{ - sensor_name_, imu_interface_names_[2], &orientation_values_[2]}; - hardware_interface::StateInterface orientation_w{ - sensor_name_, imu_interface_names_[3], &orientation_values_[4]}; + auto orientation_x = std::make_shared( + sensor_name_, imu_interface_names_[0], &orientation_values_[0]); + auto orientation_y = std::make_shared( + sensor_name_, imu_interface_names_[1], &orientation_values_[1]); + auto orientation_z = std::make_shared( + sensor_name_, imu_interface_names_[2], &orientation_values_[2]); + auto orientation_w = std::make_shared( + sensor_name_, imu_interface_names_[3], &orientation_values_[4]); // assign values to angular velocity - hardware_interface::StateInterface angular_velocity_x{ - sensor_name_, imu_interface_names_[4], &angular_velocity_values_[0]}; - hardware_interface::StateInterface angular_velocity_y{ - sensor_name_, imu_interface_names_[5], &angular_velocity_values_[1]}; - hardware_interface::StateInterface angular_velocity_z{ - sensor_name_, imu_interface_names_[6], &angular_velocity_values_[2]}; + auto angular_velocity_x = std::make_shared( + sensor_name_, imu_interface_names_[4], &angular_velocity_values_[0]); + auto angular_velocity_y = std::make_shared( + sensor_name_, imu_interface_names_[5], &angular_velocity_values_[1]); + auto angular_velocity_z = std::make_shared( + sensor_name_, imu_interface_names_[6], &angular_velocity_values_[2]); // assign values to linear acceleration - hardware_interface::StateInterface linear_acceleration_x{ - sensor_name_, imu_interface_names_[7], &linear_acceleration_values_[0]}; - hardware_interface::StateInterface linear_acceleration_y{ - sensor_name_, imu_interface_names_[8], &linear_acceleration_values_[1]}; - hardware_interface::StateInterface linear_acceleration_z{ - sensor_name_, imu_interface_names_[9], &linear_acceleration_values_[2]}; + auto linear_acceleration_x = std::make_shared( + sensor_name_, imu_interface_names_[7], &linear_acceleration_values_[0]); + auto linear_acceleration_y = std::make_shared( + sensor_name_, imu_interface_names_[8], &linear_acceleration_values_[1]); + auto linear_acceleration_z = std::make_shared( + sensor_name_, imu_interface_names_[9], &linear_acceleration_values_[2]); // create local state interface vector std::vector temp_state_interfaces; diff --git a/controller_interface/test/test_led_rgb_device.cpp b/controller_interface/test/test_led_rgb_device.cpp index 9f39726fa4..01c54c77ee 100644 --- a/controller_interface/test/test_led_rgb_device.cpp +++ b/controller_interface/test/test_led_rgb_device.cpp @@ -47,16 +47,19 @@ TEST_F(LedDeviceTest, validate_all) std::vector interface_names = led_device_->get_command_interface_names(); // Assign values to position - hardware_interface::CommandInterface led_r{device_name_, interface_names_[0], &led_values_[0]}; - hardware_interface::CommandInterface led_g{device_name_, interface_names_[1], &led_values_[1]}; - hardware_interface::CommandInterface led_b{device_name_, interface_names_[2], &led_values_[2]}; + auto led_r = std::make_shared( + device_name_, interface_names_[0], &led_values_[0]); + auto led_g = std::make_shared( + device_name_, interface_names_[1], &led_values_[1]); + auto led_b = std::make_shared( + device_name_, interface_names_[2], &led_values_[2]); // Create command interface vector in jumbled order std::vector temp_command_interfaces; temp_command_interfaces.reserve(3); - temp_command_interfaces.emplace_back(led_r); - temp_command_interfaces.emplace_back(led_g); - temp_command_interfaces.emplace_back(led_b); + temp_command_interfaces.emplace_back(led_r, nullptr); + temp_command_interfaces.emplace_back(led_g, nullptr); + temp_command_interfaces.emplace_back(led_b, nullptr); // Assign interfaces led_device_->assign_loaned_command_interfaces(temp_command_interfaces); diff --git a/controller_interface/test/test_pose_sensor.cpp b/controller_interface/test/test_pose_sensor.cpp index 6a06f2f224..6d9cf2dce9 100644 --- a/controller_interface/test/test_pose_sensor.cpp +++ b/controller_interface/test/test_pose_sensor.cpp @@ -45,22 +45,22 @@ TEST_F(PoseSensorTest, validate_all) std::vector interface_names = pose_sensor_->get_state_interface_names(); // Assign values to position - hardware_interface::StateInterface position_x{ - sensor_name_, interface_names_[0], &position_values_[0]}; - hardware_interface::StateInterface position_y{ - sensor_name_, interface_names_[1], &position_values_[1]}; - hardware_interface::StateInterface position_z{ - sensor_name_, interface_names_[2], &position_values_[2]}; + auto position_x = std::make_shared( + sensor_name_, interface_names_[0], &position_values_[0]); + auto position_y = std::make_shared( + sensor_name_, interface_names_[1], &position_values_[1]); + auto position_z = std::make_shared( + sensor_name_, interface_names_[2], &position_values_[2]); // Assign values to orientation - hardware_interface::StateInterface orientation_x{ - sensor_name_, interface_names_[3], &orientation_values_[0]}; - hardware_interface::StateInterface orientation_y{ - sensor_name_, interface_names_[4], &orientation_values_[1]}; - hardware_interface::StateInterface orientation_z{ - sensor_name_, interface_names_[5], &orientation_values_[2]}; - hardware_interface::StateInterface orientation_w{ - sensor_name_, interface_names_[6], &orientation_values_[3]}; + auto orientation_x = std::make_shared( + sensor_name_, interface_names_[3], &orientation_values_[0]); + auto orientation_y = std::make_shared( + sensor_name_, interface_names_[4], &orientation_values_[1]); + auto orientation_z = std::make_shared( + sensor_name_, interface_names_[5], &orientation_values_[2]); + auto orientation_w = std::make_shared( + sensor_name_, interface_names_[6], &orientation_values_[3]); // Create state interface vector in jumbled order std::vector temp_state_interfaces; diff --git a/controller_interface/test/test_semantic_component_command_interface.cpp b/controller_interface/test/test_semantic_component_command_interface.cpp index 07d4d54f5e..b24a658351 100644 --- a/controller_interface/test/test_semantic_component_command_interface.cpp +++ b/controller_interface/test/test_semantic_component_command_interface.cpp @@ -38,17 +38,20 @@ TEST_F(SemanticCommandInterfaceTest, validate_command_interfaces) std::vector interface_values = { std::numeric_limits::quiet_NaN(), std::numeric_limits::quiet_NaN(), std::numeric_limits::quiet_NaN()}; - hardware_interface::CommandInterface cmd_interface_1{component_name_, "1", &interface_values[0]}; - hardware_interface::CommandInterface cmd_interface_2{component_name_, "2", &interface_values[1]}; - hardware_interface::CommandInterface cmd_interface_3{component_name_, "3", &interface_values[2]}; + auto cmd_interface_1 = std::make_shared( + component_name_, "1", &interface_values[0]); + auto cmd_interface_2 = std::make_shared( + component_name_, "2", &interface_values[1]); + auto cmd_interface_3 = std::make_shared( + component_name_, "3", &interface_values[2]); // create local command interface vector std::vector temp_command_interfaces; temp_command_interfaces.reserve(3); // insert the interfaces in jumbled sequence - temp_command_interfaces.emplace_back(cmd_interface_1); - temp_command_interfaces.emplace_back(cmd_interface_3); - temp_command_interfaces.emplace_back(cmd_interface_2); + temp_command_interfaces.emplace_back(cmd_interface_1, nullptr); + temp_command_interfaces.emplace_back(cmd_interface_3, nullptr); + temp_command_interfaces.emplace_back(cmd_interface_2, nullptr); // now call the function to make them in order like interface_names EXPECT_TRUE(semantic_component_->assign_loaned_command_interfaces(temp_command_interfaces)); diff --git a/controller_interface/test/test_semantic_component_interface.cpp b/controller_interface/test/test_semantic_component_interface.cpp index 8a7817c2a3..1a0c0aa2b1 100644 --- a/controller_interface/test/test_semantic_component_interface.cpp +++ b/controller_interface/test/test_semantic_component_interface.cpp @@ -95,9 +95,12 @@ TEST_F(SemanticComponentInterfaceTest, validate_state_interfaces) std::vector interface_values = {1.1, 3.3, 5.5}; // assign 1.1 to interface_1, 3.3 to interface_3 and 5.5 to interface_5 - hardware_interface::StateInterface interface_1{component_name_, "1", &interface_values[0]}; - hardware_interface::StateInterface interface_3{component_name_, "3", &interface_values[1]}; - hardware_interface::StateInterface interface_5{component_name_, "5", &interface_values[2]}; + auto interface_1 = std::make_shared( + component_name_, "1", &interface_values[0]); + auto interface_3 = std::make_shared( + component_name_, "3", &interface_values[1]); + auto interface_5 = std::make_shared( + component_name_, "5", &interface_values[2]); // create local state interface vector std::vector temp_state_interfaces; diff --git a/hardware_interface/include/hardware_interface/handle.hpp b/hardware_interface/include/hardware_interface/handle.hpp index 6c97a465de..02a869d7b8 100644 --- a/hardware_interface/include/hardware_interface/handle.hpp +++ b/hardware_interface/include/hardware_interface/handle.hpp @@ -169,23 +169,6 @@ class Handle const std::string & get_prefix_name() const { return prefix_name_; } - [[deprecated( - "Use std::optional get_optional() instead to retrieve the value. This method will be " - "removed by the ROS 2 Kilted Kaiju release.")]] - double get_value() const - { - std::shared_lock lock(handle_mutex_, std::try_to_lock); - if (!lock.owns_lock()) - { - return std::numeric_limits::quiet_NaN(); - } - // BEGIN (Handle export change): for backward compatibility - // TODO(Manuel) return value_ if old functionality is removed - THROW_ON_NULLPTR(value_ptr_); - return *value_ptr_; - // END - } - /** * @brief Get the value of the handle. * @tparam T The type of the value to be retrieved. diff --git a/hardware_interface/include/hardware_interface/hardware_component.hpp b/hardware_interface/include/hardware_interface/hardware_component.hpp index 2d506f8bd1..c7b2cd2e98 100644 --- a/hardware_interface/include/hardware_interface/hardware_component.hpp +++ b/hardware_interface/include/hardware_interface/hardware_component.hpp @@ -51,19 +51,6 @@ class HardwareComponent final HardwareComponent & operator=(HardwareComponent && other) = delete; - [[deprecated( - "Replaced by const rclcpp_lifecycle::State & initialize(const " - "hardware_interface::HardwareComponentParams & params).")]] - const rclcpp_lifecycle::State & initialize( - const HardwareInfo & component_info, rclcpp::Logger logger, - rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface); - - [[deprecated( - "Replaced by const rclcpp_lifecycle::State & initialize(const " - "hardware_interface::HardwareComponentParams & params).")]] - const rclcpp_lifecycle::State & initialize( - const HardwareInfo & component_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock); - const rclcpp_lifecycle::State & initialize( const hardware_interface::HardwareComponentParams & params); diff --git a/hardware_interface/include/hardware_interface/hardware_component_interface.hpp b/hardware_interface/include/hardware_interface/hardware_component_interface.hpp index ae9a3602b7..534394d74f 100644 --- a/hardware_interface/include/hardware_interface/hardware_component_interface.hpp +++ b/hardware_interface/include/hardware_interface/hardware_component_interface.hpp @@ -90,28 +90,6 @@ class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::Lif virtual ~HardwareComponentInterface() = default; - /// Initialization of the hardware interface from data parsed from the robot's URDF and also the - /// clock and logger interfaces. - /** - * \param[in] hardware_info structure with data from URDF. - * \param[in] clock pointer to the resource manager clock. - * \param[in] logger Logger for the hardware component. - * \returns CallbackReturn::SUCCESS if required data are provided and can be parsed. - * \returns CallbackReturn::ERROR if any error happens or data are missing. - */ - [[deprecated( - "Replaced by CallbackReturn init(const hardware_interface::HardwareComponentParams & " - "params). Initialization is handled by the Framework.")]] - CallbackReturn init( - const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock) - { - hardware_interface::HardwareComponentParams params; - params.hardware_info = hardware_info; - params.clock = clock; - params.logger = logger; - return init(params); - }; - /// Initialization of the hardware interface from data parsed from the robot's URDF and also the /// clock and logger interfaces. /** @@ -196,14 +174,18 @@ class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::Lif /// Initialization of the hardware interface from data parsed from the robot's URDF. /** - * \param[in] hardware_info structure with data from URDF. + * \param[in] params A struct of type hardware_interface::HardwareComponentInterfaceParams + * containing all necessary parameters for initializing this specific hardware component, + * specifically its HardwareInfo, and a weak_ptr to the executor. + * \warning The parsed executor should not be used to call `cancel()` or use blocking callbacks + * such as `spin()`. * \returns CallbackReturn::SUCCESS if required data are provided and can be parsed. * \returns CallbackReturn::ERROR if any error happens or data are missing. */ - [[deprecated("Use on_init(const HardwareComponentInterfaceParams & params) instead.")]] - virtual CallbackReturn on_init(const HardwareInfo & hardware_info) + virtual CallbackReturn on_init( + const hardware_interface::HardwareComponentInterfaceParams & params) { - info_ = hardware_info; + info_ = params.hardware_info; if (info_.type == "actuator") { parse_state_interface_descriptions(info_.joints, joint_state_interfaces_); @@ -225,26 +207,6 @@ class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::Lif return CallbackReturn::SUCCESS; }; - /// Initialization of the hardware interface from data parsed from the robot's URDF. - /** - * \param[in] params A struct of type hardware_interface::HardwareComponentInterfaceParams - * containing all necessary parameters for initializing this specific hardware component, - * specifically its HardwareInfo, and a weak_ptr to the executor. - * \warning The parsed executor should not be used to call `cancel()` or use blocking callbacks - * such as `spin()`. - * \returns CallbackReturn::SUCCESS if required data are provided and can be parsed. - * \returns CallbackReturn::ERROR if any error happens or data are missing. - */ - virtual CallbackReturn on_init( - const hardware_interface::HardwareComponentInterfaceParams & params) - { - // This is done for backward compatibility with the old on_init method. -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - return on_init(params.hardware_info); -#pragma GCC diagnostic pop - }; - /// Exports all state interfaces for this hardware interface. /** * Old way of exporting the StateInterfaces. If a empty vector is returned then diff --git a/hardware_interface/include/hardware_interface/loaned_command_interface.hpp b/hardware_interface/include/hardware_interface/loaned_command_interface.hpp index 6d001bb6aa..4fa9ddf16c 100644 --- a/hardware_interface/include/hardware_interface/loaned_command_interface.hpp +++ b/hardware_interface/include/hardware_interface/loaned_command_interface.hpp @@ -31,18 +31,6 @@ class LoanedCommandInterface public: using Deleter = std::function; - [[deprecated("Replaced by the new version using shared_ptr")]] explicit LoanedCommandInterface( - CommandInterface & command_interface) - : LoanedCommandInterface(command_interface, nullptr) - { - } - - [[deprecated("Replaced by the new version using shared_ptr")]] LoanedCommandInterface( - CommandInterface & command_interface, Deleter && deleter) - : command_interface_(command_interface), deleter_(std::forward(deleter)) - { - } - LoanedCommandInterface(CommandInterface::SharedPtr command_interface, Deleter && deleter) : command_interface_(*command_interface), deleter_(std::forward(deleter)) { @@ -121,22 +109,6 @@ class LoanedCommandInterface return true; } - [[deprecated( - "Use std::optional get_optional() instead to retrieve the value. This method will be " - "removed by the ROS 2 Kilted Kaiju release.")]] - double get_value() const - { - std::optional opt_value = get_optional(); - if (opt_value.has_value()) - { - return opt_value.value(); - } - else - { - return std::numeric_limits::quiet_NaN(); - } - } - /** * @brief Get the value of the command interface. * @tparam T The type of the value to be retrieved. diff --git a/hardware_interface/include/hardware_interface/loaned_state_interface.hpp b/hardware_interface/include/hardware_interface/loaned_state_interface.hpp index 6b74160603..795943d650 100644 --- a/hardware_interface/include/hardware_interface/loaned_state_interface.hpp +++ b/hardware_interface/include/hardware_interface/loaned_state_interface.hpp @@ -30,18 +30,6 @@ class LoanedStateInterface public: using Deleter = std::function; - [[deprecated("Replaced by the new version using shared_ptr")]] explicit LoanedStateInterface( - const StateInterface & state_interface) - : LoanedStateInterface(state_interface, nullptr) - { - } - - [[deprecated("Replaced by the new version using shared_ptr")]] LoanedStateInterface( - const StateInterface & state_interface, Deleter && deleter) - : state_interface_(state_interface), deleter_(std::forward(deleter)) - { - } - explicit LoanedStateInterface(StateInterface::ConstSharedPtr state_interface) : LoanedStateInterface(state_interface, nullptr) { @@ -81,22 +69,6 @@ class LoanedStateInterface const std::string & get_prefix_name() const { return state_interface_.get_prefix_name(); } - [[deprecated( - "Use std::optional get_optional() instead to retrieve the value. This method will be " - "removed by the ROS 2 Kilted Kaiju release.")]] - double get_value() const - { - std::optional opt_value = get_optional(); - if (opt_value.has_value()) - { - return opt_value.value(); - } - else - { - return std::numeric_limits::quiet_NaN(); - } - } - /** * @brief Get the value of the state interface. * @tparam T The type of the value to be retrieved. diff --git a/hardware_interface/include/hardware_interface/resource_manager.hpp b/hardware_interface/include/hardware_interface/resource_manager.hpp index a443c08dba..cda12d8f19 100644 --- a/hardware_interface/include/hardware_interface/resource_manager.hpp +++ b/hardware_interface/include/hardware_interface/resource_manager.hpp @@ -124,20 +124,6 @@ class ResourceManager */ bool shutdown_components(); - /// Load resources from on a given URDF. - /** - * The resource manager can be post-initialized with a given URDF. - * This is mainly used in conjunction with the default constructor - * in which the URDF might not be present at first initialization. - * - * \param[in] urdf string containing the URDF. - * \param[in] update_rate update rate of the main control loop, i.e., of the controller manager. - * \returns false if URDF validation has failed. - */ - [[deprecated("Use load_and_initialize_components(const ResourceManagerParams & params) instead")]] - virtual bool load_and_initialize_components( - const std::string & urdf, const unsigned int update_rate = 100); - /// Load resources from on a given URDF. /** * The resource manager can be post-initialized with a given URDF. @@ -402,44 +388,6 @@ class ResourceManager */ size_t system_components_size() const; - /// Import a hardware component which is not listed in the URDF - /** - * Components which are initialized outside a URDF can be added post initialization. - * Nevertheless, there should still be `HardwareInfo` available for this component, - * either parsed from a URDF string (easiest) or filled manually. - * - * \note this might invalidate existing state and command interfaces and should thus - * not be called when a controller is running. - * \note given that no hardware_info is available, the component has to be configured - * externally and prior to the call to import. - * \param[in] actuator pointer to the actuator interface. - * \param[in] hardware_info hardware info - */ - [[deprecated( - "Use import_component(std::unique_ptr actuator, " - "const HardwareComponentParams & params) instead")]] - void import_component( - std::unique_ptr actuator, const HardwareInfo & hardware_info); - - /// Import a hardware component which is not listed in the URDF - /** - * Components which are initialized outside a URDF can be added post initialization. - * Nevertheless, there should still be `HardwareInfo` available for this component, - * either parsed from a URDF string (easiest) or filled manually. - * - * \note this might invalidate existing state and command interfaces and should thus - * not be called when a controller is running. - * \note given that no hardware_info is available, the component has to be configured - * externally and prior to the call to import. - * \param[in] sensor pointer to the sensor interface. - * \param[in] hardware_info hardware info - */ - [[deprecated( - "Use import_component(std::unique_ptr sensor, " - "const HardwareComponentParams & params) instead")]] - void import_component( - std::unique_ptr sensor, const HardwareInfo & hardware_info); - /// Import a hardware component which is not listed in the URDF /** * Components which are initialized outside a URDF can be added post initialization. @@ -490,26 +438,6 @@ class ResourceManager void import_component( std::unique_ptr sensor, const HardwareComponentParams & params); - /// Import a hardware component which is not listed in the URDF - /** - * Components which are initialized outside a URDF can be added post initialization. - * Nevertheless, there should still be `HardwareInfo` available for this component, - * either parsed from a URDF string (easiest) or filled manually. - * - * \note this might invalidate existing state and command interfaces and should thus - * not be called when a controller is running. - * \note given that no hardware_info is available, the component has to be configured - * externally and prior to the call to import. - * \param[in] system pointer to the system interface. - * \param[in] params Struct of type HardwareComponentParams containing the hardware info - * and other parameters for the component. - */ - [[deprecated( - "Use import_component(std::unique_ptr system, " - "const HardwareComponentParams & params) instead")]] - void import_component( - std::unique_ptr system, const HardwareInfo & hardware_info); - /// Return status for all components. /** * \return map of hardware names and their status. diff --git a/hardware_interface/src/hardware_component.cpp b/hardware_interface/src/hardware_component.cpp index 9a9f0f0f5f..25f0b5e851 100644 --- a/hardware_interface/src/hardware_component.cpp +++ b/hardware_interface/src/hardware_component.cpp @@ -46,27 +46,6 @@ HardwareComponent::HardwareComponent(HardwareComponent && other) noexcept last_write_cycle_time_ = rclcpp::Time(0, 0, RCL_CLOCK_UNINITIALIZED); } -const rclcpp_lifecycle::State & HardwareComponent::initialize( - const HardwareInfo & hardware_info, rclcpp::Logger logger, - rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface) -{ - // This is done for backward compatibility with the old initialize method. -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - return this->initialize(hardware_info, logger, clock_interface->get_clock()); -#pragma GCC diagnostic pop -} - -const rclcpp_lifecycle::State & HardwareComponent::initialize( - const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock) -{ - hardware_interface::HardwareComponentParams params; - params.hardware_info = hardware_info; - params.logger = logger; - params.clock = clock; - return initialize(params); -} - const rclcpp_lifecycle::State & HardwareComponent::initialize( const hardware_interface::HardwareComponentParams & params) { diff --git a/hardware_interface/src/resource_manager.cpp b/hardware_interface/src/resource_manager.cpp index 249fbfa251..c6b9220813 100644 --- a/hardware_interface/src/resource_manager.cpp +++ b/hardware_interface/src/resource_manager.cpp @@ -1445,15 +1445,6 @@ bool ResourceManager::shutdown_components() } // CM API: Called in "callback/slow"-thread -bool ResourceManager::load_and_initialize_components( - const std::string & urdf, const unsigned int update_rate) -{ - hardware_interface::ResourceManagerParams params; - params.robot_description = urdf; - params.update_rate = update_rate; - return load_and_initialize_components(params); -} - bool ResourceManager::load_and_initialize_components( const hardware_interface::ResourceManagerParams & params) { @@ -1883,30 +1874,6 @@ std::string ResourceManager::get_command_interface_data_type(const std::string & } } -void ResourceManager::import_component( - std::unique_ptr actuator, const HardwareInfo & hardware_info) -{ - HardwareComponentParams params; - params.hardware_info = hardware_info; - import_component(std::move(actuator), params); -} - -void ResourceManager::import_component( - std::unique_ptr sensor, const HardwareInfo & hardware_info) -{ - HardwareComponentParams params; - params.hardware_info = hardware_info; - import_component(std::move(sensor), params); -} - -void ResourceManager::import_component( - std::unique_ptr system, const HardwareInfo & hardware_info) -{ - HardwareComponentParams params; - params.hardware_info = hardware_info; - import_component(std::move(system), params); -} - void ResourceManager::import_component( std::unique_ptr actuator, const HardwareComponentParams & params) { diff --git a/hardware_interface_testing/test/test_resource_manager.cpp b/hardware_interface_testing/test/test_resource_manager.cpp index 1112c1c742..f7b75faed8 100644 --- a/hardware_interface_testing/test/test_resource_manager.cpp +++ b/hardware_interface_testing/test/test_resource_manager.cpp @@ -99,11 +99,6 @@ TEST_F(ResourceManagerTest, initialization_with_urdf) TEST_F(ResourceManagerTest, post_initialization_with_urdf) { TestableResourceManager rm(node_); -// TODO(saikishor) : remove after the cleanup of deprecated API -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - ASSERT_NO_THROW(rm.load_and_initialize_components(ros2_control_test_assets::minimal_robot_urdf)); -#pragma GCC diagnostic pop hardware_interface::ResourceManagerParams rm_params; rm_params.robot_description = ros2_control_test_assets::minimal_robot_urdf; rm_params.update_rate = 100; @@ -114,11 +109,10 @@ void test_load_and_initialized_components_failure(const std::string & urdf) { rclcpp::Node node = rclcpp::Node("TestableResourceManager"); TestableResourceManager rm(node); -// TODO(saikishor) : remove after the cleanup of deprecated API -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - ASSERT_FALSE(rm.load_and_initialize_components(urdf)); -#pragma GCC diagnostic pop + hardware_interface::ResourceManagerParams rm_params; + rm_params.robot_description = urdf; + rm_params.update_rate = 100; + ASSERT_NO_THROW(rm.load_and_initialize_components(rm_params)); ASSERT_FALSE(rm.are_components_initialized()); @@ -277,18 +271,6 @@ TEST_F(ResourceManagerTest, load_and_initialize_components_called_if_async_urdf_ ASSERT_TRUE(rm.are_components_initialized()); } -TEST_F(ResourceManagerTest, can_load_and_initialize_components_later) -{ - TestableResourceManager rm(node_); - ASSERT_FALSE(rm.are_components_initialized()); -// TODO(saikishor) : remove after the cleanup of deprecated API -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - rm.load_and_initialize_components(ros2_control_test_assets::minimal_robot_urdf); -#pragma GCC diagnostic pop - ASSERT_TRUE(rm.are_components_initialized()); -} - TEST_F(ResourceManagerTest, resource_claiming) { TestableResourceManager rm(node_, ros2_control_test_assets::minimal_robot_urdf); From 01f1ffdd73429b47e9f8f610efc6a99c16db081d Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Thu, 2 Oct 2025 14:42:37 +0900 Subject: [PATCH 2/5] Add constructor with null deleter --- .../include/hardware_interface/loaned_command_interface.hpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/hardware_interface/include/hardware_interface/loaned_command_interface.hpp b/hardware_interface/include/hardware_interface/loaned_command_interface.hpp index 4fa9ddf16c..9d286c65e3 100644 --- a/hardware_interface/include/hardware_interface/loaned_command_interface.hpp +++ b/hardware_interface/include/hardware_interface/loaned_command_interface.hpp @@ -31,6 +31,11 @@ class LoanedCommandInterface public: using Deleter = std::function; + explicit LoanedCommandInterface(CommandInterface::SharedPtr command_interface) + : LoanedCommandInterface(command_interface, nullptr) + { + } + LoanedCommandInterface(CommandInterface::SharedPtr command_interface, Deleter && deleter) : command_interface_(*command_interface), deleter_(std::forward(deleter)) { From 765361a1d8d179a186e6acacb66669bdc09be58e Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Thu, 2 Oct 2025 14:45:02 +0900 Subject: [PATCH 3/5] mark both the constructors explicit --- .../include/hardware_interface/loaned_command_interface.hpp | 2 +- .../include/hardware_interface/loaned_state_interface.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/hardware_interface/include/hardware_interface/loaned_command_interface.hpp b/hardware_interface/include/hardware_interface/loaned_command_interface.hpp index 9d286c65e3..08ae5d0d1f 100644 --- a/hardware_interface/include/hardware_interface/loaned_command_interface.hpp +++ b/hardware_interface/include/hardware_interface/loaned_command_interface.hpp @@ -36,7 +36,7 @@ class LoanedCommandInterface { } - LoanedCommandInterface(CommandInterface::SharedPtr command_interface, Deleter && deleter) + explicit LoanedCommandInterface(CommandInterface::SharedPtr command_interface, Deleter && deleter) : command_interface_(*command_interface), deleter_(std::forward(deleter)) { } diff --git a/hardware_interface/include/hardware_interface/loaned_state_interface.hpp b/hardware_interface/include/hardware_interface/loaned_state_interface.hpp index 795943d650..ab2720af37 100644 --- a/hardware_interface/include/hardware_interface/loaned_state_interface.hpp +++ b/hardware_interface/include/hardware_interface/loaned_state_interface.hpp @@ -35,7 +35,7 @@ class LoanedStateInterface { } - LoanedStateInterface(StateInterface::ConstSharedPtr state_interface, Deleter && deleter) + explicit LoanedStateInterface(StateInterface::ConstSharedPtr state_interface, Deleter && deleter) : state_interface_(*state_interface), deleter_(std::forward(deleter)) { } From 52fa4a066e6e83a06d1bdbe37be118aa31e60f83 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Thu, 2 Oct 2025 07:29:39 +0000 Subject: [PATCH 4/5] Exclude our own downstream packages --- .github/workflows/humble-pre-release.yml | 1 + .github/workflows/jazzy-pre-release.yml | 1 + .github/workflows/rolling-pre-release.yml | 1 + 3 files changed, 3 insertions(+) diff --git a/.github/workflows/humble-pre-release.yml b/.github/workflows/humble-pre-release.yml index a8a4dab1a0..f54d97745d 100644 --- a/.github/workflows/humble-pre-release.yml +++ b/.github/workflows/humble-pre-release.yml @@ -25,3 +25,4 @@ jobs: ros_distro: humble # downstream_depth is not set on pull_request event prerelease_downstream_depth: ${{ github.event_name == 'pull_request' && '0' || inputs.downstream_depth }} + prerelease_exclude_pkg: ackermann_steering_controller admittance_controller bicycle_steering_controller chained_filter_controller diff_drive_controller effort_controllers force_torque_sensor_broadcaster forward_command_controller gpio_controllers gps_sensor_broadcaster imu_sensor_broadcaster joint_state_broadcaster joint_trajectory_controller mecanum_drive_controller motion_primitives_controllers omni_wheel_drive_controller parallel_gripper_controller pid_controller pose_broadcaster position_controllers range_sensor_broadcaster ros2_controllers ros2_controllers_test_nodes rqt_joint_trajectory_controller steering_controllers_library tricycle_controller tricycle_steering_controller velocity_controllers gz_ros2_control gz_ros2_control_demos gz_ros2_control_tests diff --git a/.github/workflows/jazzy-pre-release.yml b/.github/workflows/jazzy-pre-release.yml index 0ab61dfcd9..18a3a0a78b 100644 --- a/.github/workflows/jazzy-pre-release.yml +++ b/.github/workflows/jazzy-pre-release.yml @@ -25,3 +25,4 @@ jobs: ros_distro: jazzy # downstream_depth is not set on pull_request event prerelease_downstream_depth: ${{ github.event_name == 'pull_request' && '0' || inputs.downstream_depth }} + prerelease_exclude_pkg: ackermann_steering_controller admittance_controller bicycle_steering_controller chained_filter_controller diff_drive_controller effort_controllers force_torque_sensor_broadcaster forward_command_controller gpio_controllers gps_sensor_broadcaster imu_sensor_broadcaster joint_state_broadcaster joint_trajectory_controller mecanum_drive_controller motion_primitives_controllers omni_wheel_drive_controller parallel_gripper_controller pid_controller pose_broadcaster position_controllers range_sensor_broadcaster ros2_controllers ros2_controllers_test_nodes rqt_joint_trajectory_controller steering_controllers_library tricycle_controller tricycle_steering_controller velocity_controllers gz_ros2_control gz_ros2_control_demos gz_ros2_control_tests diff --git a/.github/workflows/rolling-pre-release.yml b/.github/workflows/rolling-pre-release.yml index 95609af1cd..0424a975c8 100644 --- a/.github/workflows/rolling-pre-release.yml +++ b/.github/workflows/rolling-pre-release.yml @@ -30,3 +30,4 @@ jobs: ros_distro: ${{ matrix.ROS_DISTRO }} # downstream_depth is not set on pull_request event prerelease_downstream_depth: ${{ github.event_name == 'pull_request' && '0' || inputs.downstream_depth }} + prerelease_exclude_pkg: ackermann_steering_controller admittance_controller bicycle_steering_controller chained_filter_controller diff_drive_controller effort_controllers force_torque_sensor_broadcaster forward_command_controller gpio_controllers gps_sensor_broadcaster imu_sensor_broadcaster joint_state_broadcaster joint_trajectory_controller mecanum_drive_controller motion_primitives_controllers omni_wheel_drive_controller parallel_gripper_controller pid_controller pose_broadcaster position_controllers range_sensor_broadcaster ros2_controllers ros2_controllers_test_nodes rqt_joint_trajectory_controller steering_controllers_library tricycle_controller tricycle_steering_controller velocity_controllers gz_ros2_control gz_ros2_control_demos gz_ros2_control_tests From 87eaf044094d925fcb833166963f4503b7f2100f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Thu, 2 Oct 2025 12:30:11 +0200 Subject: [PATCH 5/5] Use constructor without deleter Co-authored-by: Sai Kishor Kothakota --- .../test/test_force_torque_sensor.cpp | 12 ++++++------ controller_interface/test/test_led_rgb_device.cpp | 6 +++--- .../test_semantic_component_command_interface.cpp | 6 +++--- 3 files changed, 12 insertions(+), 12 deletions(-) diff --git a/controller_interface/test/test_force_torque_sensor.cpp b/controller_interface/test/test_force_torque_sensor.cpp index 315c04999d..8f8405054e 100644 --- a/controller_interface/test/test_force_torque_sensor.cpp +++ b/controller_interface/test/test_force_torque_sensor.cpp @@ -233,12 +233,12 @@ TEST_F(ForceTorqueSensorTest, validate_all_custom_names) std::vector temp_state_interfaces; // insert the interfaces in jumbled sequence - temp_state_interfaces.emplace_back(torque_y, nullptr); - temp_state_interfaces.emplace_back(force_z, nullptr); - temp_state_interfaces.emplace_back(force_x, nullptr); - temp_state_interfaces.emplace_back(torque_z, nullptr); - temp_state_interfaces.emplace_back(torque_x, nullptr); - temp_state_interfaces.emplace_back(force_y, nullptr); + temp_state_interfaces.emplace_back(torque_y); + temp_state_interfaces.emplace_back(force_z); + temp_state_interfaces.emplace_back(force_x); + temp_state_interfaces.emplace_back(torque_z); + temp_state_interfaces.emplace_back(torque_x); + temp_state_interfaces.emplace_back(force_y); // now call the function to make them in order like interface_names force_torque_sensor_->assign_loaned_state_interfaces(temp_state_interfaces); diff --git a/controller_interface/test/test_led_rgb_device.cpp b/controller_interface/test/test_led_rgb_device.cpp index 01c54c77ee..4be4242b1e 100644 --- a/controller_interface/test/test_led_rgb_device.cpp +++ b/controller_interface/test/test_led_rgb_device.cpp @@ -57,9 +57,9 @@ TEST_F(LedDeviceTest, validate_all) // Create command interface vector in jumbled order std::vector temp_command_interfaces; temp_command_interfaces.reserve(3); - temp_command_interfaces.emplace_back(led_r, nullptr); - temp_command_interfaces.emplace_back(led_g, nullptr); - temp_command_interfaces.emplace_back(led_b, nullptr); + temp_command_interfaces.emplace_back(led_r); + temp_command_interfaces.emplace_back(led_g); + temp_command_interfaces.emplace_back(led_b); // Assign interfaces led_device_->assign_loaned_command_interfaces(temp_command_interfaces); diff --git a/controller_interface/test/test_semantic_component_command_interface.cpp b/controller_interface/test/test_semantic_component_command_interface.cpp index b24a658351..1251e5f4d5 100644 --- a/controller_interface/test/test_semantic_component_command_interface.cpp +++ b/controller_interface/test/test_semantic_component_command_interface.cpp @@ -49,9 +49,9 @@ TEST_F(SemanticCommandInterfaceTest, validate_command_interfaces) std::vector temp_command_interfaces; temp_command_interfaces.reserve(3); // insert the interfaces in jumbled sequence - temp_command_interfaces.emplace_back(cmd_interface_1, nullptr); - temp_command_interfaces.emplace_back(cmd_interface_3, nullptr); - temp_command_interfaces.emplace_back(cmd_interface_2, nullptr); + temp_command_interfaces.emplace_back(cmd_interface_1); + temp_command_interfaces.emplace_back(cmd_interface_3); + temp_command_interfaces.emplace_back(cmd_interface_2); // now call the function to make them in order like interface_names EXPECT_TRUE(semantic_component_->assign_loaned_command_interfaces(temp_command_interfaces));