From 1cabf60267c5a949c577911df8f2a53a511f87f4 Mon Sep 17 00:00:00 2001 From: Soham Patil Date: Tue, 14 Oct 2025 07:20:26 +0000 Subject: [PATCH 1/4] fixed tests for component interfaces --- .../test/test_component_interfaces.cpp | 65 ++++++++++++++++--- ...est_component_interfaces_custom_export.cpp | 7 ++ 2 files changed, 63 insertions(+), 9 deletions(-) diff --git a/hardware_interface/test/test_component_interfaces.cpp b/hardware_interface/test/test_component_interfaces.cpp index c67c0fd2f5..c955d7f700 100644 --- a/hardware_interface/test/test_component_interfaces.cpp +++ b/hardware_interface/test/test_component_interfaces.cpp @@ -32,6 +32,7 @@ #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "hardware_interface/types/lifecycle_state_names.hpp" #include "lifecycle_msgs/msg/state.hpp" +#include "rclcpp/executors/single_threaded_executor.hpp" #include "rclcpp/node.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "ros2_control_test_assets/components_urdfs.hpp" @@ -769,12 +770,15 @@ TEST(TestComponentInterfaces, dummy_actuator) { hardware_interface::Actuator actuator_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_actuator_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -880,6 +884,8 @@ TEST(TestComponentInterfaces, dummy_actuator_default) params.hardware_info = dummy_actuator; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); @@ -997,12 +1003,15 @@ TEST(TestComponentInterfaces, dummy_sensor) { hardware_interface::Sensor sensor_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_sensor_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = sensor_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1046,6 +1055,8 @@ TEST(TestComponentInterfaces, dummy_sensor_default) params.hardware_info = voltage_sensor_res; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = sensor_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1094,6 +1105,8 @@ TEST(TestComponentInterfaces, dummy_sensor_default_joint) params.hardware_info = sensor_res; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = sensor_hw.initialize(params); ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); ASSERT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1140,12 +1153,15 @@ TEST(TestComponentInterfaces, dummy_system) { hardware_interface::System system_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1285,6 +1301,8 @@ TEST(TestComponentInterfaces, dummy_system_default) params.hardware_info = dummy_system; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1489,12 +1507,16 @@ TEST(TestComponentInterfaces, dummy_command_mode_system) { hardware_interface::System system_hw( std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1526,12 +1548,15 @@ TEST(TestComponentInterfaces, dummy_actuator_read_error_behavior) { hardware_interface::Actuator actuator_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_actuator_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1604,6 +1629,8 @@ TEST(TestComponentInterfaces, dummy_actuator_default_read_error_behavior) params.hardware_info = dummy_actuator; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); @@ -1667,12 +1694,15 @@ TEST(TestComponentInterfaces, dummy_actuator_write_error_behavior) { hardware_interface::Actuator actuator_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_actuator_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1745,6 +1775,8 @@ TEST(TestComponentInterfaces, dummy_actuator_default_write_error_behavior) params.hardware_info = dummy_actuator; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1807,12 +1839,15 @@ TEST(TestComponentInterfaces, dummy_sensor_read_error_behavior) { hardware_interface::Sensor sensor_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_sensor_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = sensor_hw.initialize(params); auto state_interfaces = sensor_hw.export_state_interfaces(); @@ -1889,6 +1924,8 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior) params.hardware_info = voltage_sensor_res; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = sensor_hw.initialize(params); auto state_interfaces = sensor_hw.export_state_interfaces(); @@ -1942,12 +1979,15 @@ TEST(TestComponentInterfaces, dummy_system_read_error_behavior) { hardware_interface::System system_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -2024,6 +2064,8 @@ TEST(TestComponentInterfaces, dummy_system_default_read_error_behavior) params.hardware_info = dummy_system; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -2088,12 +2130,15 @@ TEST(TestComponentInterfaces, dummy_system_write_error_behavior) { hardware_interface::System system_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -2170,6 +2215,8 @@ TEST(TestComponentInterfaces, dummy_system_default_write_error_behavior) params.hardware_info = dummy_system; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); diff --git a/hardware_interface/test/test_component_interfaces_custom_export.cpp b/hardware_interface/test/test_component_interfaces_custom_export.cpp index 80e9ab83f9..f2db4ec823 100644 --- a/hardware_interface/test/test_component_interfaces_custom_export.cpp +++ b/hardware_interface/test/test_component_interfaces_custom_export.cpp @@ -32,6 +32,7 @@ #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "hardware_interface/types/lifecycle_state_names.hpp" #include "lifecycle_msgs/msg/state.hpp" +#include "rclcpp/executors/single_threaded_executor.hpp" #include "rclcpp/node.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "ros2_control_test_assets/components_urdfs.hpp" @@ -167,6 +168,8 @@ TEST(TestComponentInterfaces, dummy_actuator_default_custom_export) params.hardware_info = dummy_actuator; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); @@ -236,6 +239,8 @@ TEST(TestComponentInterfaces, dummy_sensor_default_custom_export) params.hardware_info = voltage_sensor_res; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = sensor_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -276,6 +281,8 @@ TEST(TestComponentInterfaces, dummy_system_default_custom_export) params.hardware_info = dummy_system; params.clock = node->get_clock(); params.logger = node->get_logger(); + auto executor = std::make_shared(); + params.executor = executor; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); From 297bc5c6761f6f156d512670dd2dec913c827de1 Mon Sep 17 00:00:00 2001 From: Soham Patil Date: Fri, 24 Oct 2025 13:04:49 +0000 Subject: [PATCH 2/4] Revert "fixed tests for component interfaces" This reverts commit 1cabf60267c5a949c577911df8f2a53a511f87f4. --- .../test/test_component_interfaces.cpp | 65 +++---------------- ...est_component_interfaces_custom_export.cpp | 7 -- 2 files changed, 9 insertions(+), 63 deletions(-) diff --git a/hardware_interface/test/test_component_interfaces.cpp b/hardware_interface/test/test_component_interfaces.cpp index b1a64d01a8..81bcc020dd 100644 --- a/hardware_interface/test/test_component_interfaces.cpp +++ b/hardware_interface/test/test_component_interfaces.cpp @@ -32,7 +32,6 @@ #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "hardware_interface/types/lifecycle_state_names.hpp" #include "lifecycle_msgs/msg/state.hpp" -#include "rclcpp/executors/single_threaded_executor.hpp" #include "rclcpp/node.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "ros2_control_test_assets/components_urdfs.hpp" @@ -785,15 +784,12 @@ TEST(TestComponentInterfaces, dummy_actuator) { hardware_interface::Actuator actuator_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info; - mock_hw_info.name = "mock_hw"; + hardware_interface::HardwareInfo mock_hw_info{}; rclcpp::Node::SharedPtr node = std::make_shared("test_actuator_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -899,8 +895,6 @@ TEST(TestComponentInterfaces, dummy_actuator_default) params.hardware_info = dummy_actuator; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); @@ -1018,15 +1012,12 @@ TEST(TestComponentInterfaces, dummy_sensor) { hardware_interface::Sensor sensor_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info; - mock_hw_info.name = "mock_hw"; + hardware_interface::HardwareInfo mock_hw_info{}; rclcpp::Node::SharedPtr node = std::make_shared("test_sensor_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = sensor_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1070,8 +1061,6 @@ TEST(TestComponentInterfaces, dummy_sensor_default) params.hardware_info = voltage_sensor_res; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = sensor_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1120,8 +1109,6 @@ TEST(TestComponentInterfaces, dummy_sensor_default_joint) params.hardware_info = sensor_res; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = sensor_hw.initialize(params); ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); ASSERT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1168,15 +1155,12 @@ TEST(TestComponentInterfaces, dummy_system) { hardware_interface::System system_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info; - mock_hw_info.name = "mock_hw"; + hardware_interface::HardwareInfo mock_hw_info{}; rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1316,8 +1300,6 @@ TEST(TestComponentInterfaces, dummy_system_default) params.hardware_info = dummy_system; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1522,16 +1504,12 @@ TEST(TestComponentInterfaces, dummy_command_mode_system) { hardware_interface::System system_hw( std::make_unique()); - - hardware_interface::HardwareInfo mock_hw_info; - mock_hw_info.name = "mock_hw"; + hardware_interface::HardwareInfo mock_hw_info{}; rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1563,15 +1541,12 @@ TEST(TestComponentInterfaces, dummy_actuator_read_error_behavior) { hardware_interface::Actuator actuator_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info; - mock_hw_info.name = "mock_hw"; + hardware_interface::HardwareInfo mock_hw_info{}; rclcpp::Node::SharedPtr node = std::make_shared("test_actuator_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1644,8 +1619,6 @@ TEST(TestComponentInterfaces, dummy_actuator_default_read_error_behavior) params.hardware_info = dummy_actuator; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); @@ -1709,15 +1682,12 @@ TEST(TestComponentInterfaces, dummy_actuator_write_error_behavior) { hardware_interface::Actuator actuator_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info; - mock_hw_info.name = "mock_hw"; + hardware_interface::HardwareInfo mock_hw_info{}; rclcpp::Node::SharedPtr node = std::make_shared("test_actuator_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1790,8 +1760,6 @@ TEST(TestComponentInterfaces, dummy_actuator_default_write_error_behavior) params.hardware_info = dummy_actuator; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1854,15 +1822,12 @@ TEST(TestComponentInterfaces, dummy_sensor_read_error_behavior) { hardware_interface::Sensor sensor_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info; - mock_hw_info.name = "mock_hw"; + hardware_interface::HardwareInfo mock_hw_info{}; rclcpp::Node::SharedPtr node = std::make_shared("test_sensor_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = sensor_hw.initialize(params); auto state_interfaces = sensor_hw.export_state_interfaces(); @@ -1939,8 +1904,6 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior) params.hardware_info = voltage_sensor_res; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = sensor_hw.initialize(params); auto state_interfaces = sensor_hw.export_state_interfaces(); @@ -1994,15 +1957,12 @@ TEST(TestComponentInterfaces, dummy_system_read_error_behavior) { hardware_interface::System system_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info; - mock_hw_info.name = "mock_hw"; + hardware_interface::HardwareInfo mock_hw_info{}; rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -2079,8 +2039,6 @@ TEST(TestComponentInterfaces, dummy_system_default_read_error_behavior) params.hardware_info = dummy_system; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -2145,15 +2103,12 @@ TEST(TestComponentInterfaces, dummy_system_write_error_behavior) { hardware_interface::System system_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info; - mock_hw_info.name = "mock_hw"; + hardware_interface::HardwareInfo mock_hw_info{}; rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -2230,8 +2185,6 @@ TEST(TestComponentInterfaces, dummy_system_default_write_error_behavior) params.hardware_info = dummy_system; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); diff --git a/hardware_interface/test/test_component_interfaces_custom_export.cpp b/hardware_interface/test/test_component_interfaces_custom_export.cpp index f2db4ec823..80e9ab83f9 100644 --- a/hardware_interface/test/test_component_interfaces_custom_export.cpp +++ b/hardware_interface/test/test_component_interfaces_custom_export.cpp @@ -32,7 +32,6 @@ #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "hardware_interface/types/lifecycle_state_names.hpp" #include "lifecycle_msgs/msg/state.hpp" -#include "rclcpp/executors/single_threaded_executor.hpp" #include "rclcpp/node.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "ros2_control_test_assets/components_urdfs.hpp" @@ -168,8 +167,6 @@ TEST(TestComponentInterfaces, dummy_actuator_default_custom_export) params.hardware_info = dummy_actuator; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); @@ -239,8 +236,6 @@ TEST(TestComponentInterfaces, dummy_sensor_default_custom_export) params.hardware_info = voltage_sensor_res; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = sensor_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -281,8 +276,6 @@ TEST(TestComponentInterfaces, dummy_system_default_custom_export) params.hardware_info = dummy_system; params.clock = node->get_clock(); params.logger = node->get_logger(); - auto executor = std::make_shared(); - params.executor = executor; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); From b88ddb834f1ba79e1bd357c15c6be6ad50bd67e6 Mon Sep 17 00:00:00 2001 From: Soham Patil Date: Fri, 24 Oct 2025 13:26:02 +0000 Subject: [PATCH 3/4] fixed tests for component interfaces --- .../test/test_component_interfaces.cpp | 97 +++++++++++++------ ...est_component_interfaces_custom_export.cpp | 24 ++++- 2 files changed, 91 insertions(+), 30 deletions(-) diff --git a/hardware_interface/test/test_component_interfaces.cpp b/hardware_interface/test/test_component_interfaces.cpp index 81bcc020dd..75e445d3f7 100644 --- a/hardware_interface/test/test_component_interfaces.cpp +++ b/hardware_interface/test/test_component_interfaces.cpp @@ -32,6 +32,7 @@ #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "hardware_interface/types/lifecycle_state_names.hpp" #include "lifecycle_msgs/msg/state.hpp" +#include "rclcpp/executors/multi_threaded_executor.hpp" #include "rclcpp/node.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "ros2_control_test_assets/components_urdfs.hpp" @@ -778,18 +779,34 @@ class DummySystemPreparePerform : public hardware_interface::SystemInterface }; } // namespace test_components +class TestComponentInterfaces : public ::testing::Test +{ +protected: + void SetUp() override + { + if (!rclcpp::ok()) + { + rclcpp::init(0, nullptr); + } + executor_ = std::make_shared(); + } + void TearDown() override { rclcpp::shutdown(); } + std::shared_ptr executor_; +}; // BEGIN (Handle export change): for backward compatibility -TEST(TestComponentInterfaces, dummy_actuator) +TEST_F(TestComponentInterfaces, dummy_actuator) { hardware_interface::Actuator actuator_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_actuator_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -879,7 +896,7 @@ TEST(TestComponentInterfaces, dummy_actuator) } // END -TEST(TestComponentInterfaces, dummy_actuator_default) +TEST_F(TestComponentInterfaces, dummy_actuator_default) { hardware_interface::Actuator actuator_hw( std::make_unique()); @@ -895,6 +912,7 @@ TEST(TestComponentInterfaces, dummy_actuator_default) params.hardware_info = dummy_actuator; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); @@ -1008,16 +1026,18 @@ TEST(TestComponentInterfaces, dummy_actuator_default) } // BEGIN (Handle export change): for backward compatibility -TEST(TestComponentInterfaces, dummy_sensor) +TEST_F(TestComponentInterfaces, dummy_sensor) { hardware_interface::Sensor sensor_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_sensor_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = sensor_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1045,7 +1065,7 @@ TEST(TestComponentInterfaces, dummy_sensor) } // END -TEST(TestComponentInterfaces, dummy_sensor_default) +TEST_F(TestComponentInterfaces, dummy_sensor_default) { hardware_interface::Sensor sensor_hw(std::make_unique()); @@ -1061,6 +1081,7 @@ TEST(TestComponentInterfaces, dummy_sensor_default) params.hardware_info = voltage_sensor_res; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = sensor_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1092,7 +1113,7 @@ TEST(TestComponentInterfaces, dummy_sensor_default) EXPECT_EQ(0x666, state_interfaces[si_sens1_vol]->get_optional().value()); } -TEST(TestComponentInterfaces, dummy_sensor_default_joint) +TEST_F(TestComponentInterfaces, dummy_sensor_default_joint) { hardware_interface::Sensor sensor_hw( std::make_unique()); @@ -1109,6 +1130,7 @@ TEST(TestComponentInterfaces, dummy_sensor_default_joint) params.hardware_info = sensor_res; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = sensor_hw.initialize(params); ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); ASSERT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1151,16 +1173,18 @@ TEST(TestComponentInterfaces, dummy_sensor_default_joint) } // BEGIN (Handle export change): for backward compatibility -TEST(TestComponentInterfaces, dummy_system) +TEST_F(TestComponentInterfaces, dummy_system) { hardware_interface::System system_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1284,7 +1308,7 @@ TEST(TestComponentInterfaces, dummy_system) } // END -TEST(TestComponentInterfaces, dummy_system_default) +TEST_F(TestComponentInterfaces, dummy_system_default) { hardware_interface::System system_hw(std::make_unique()); @@ -1300,6 +1324,7 @@ TEST(TestComponentInterfaces, dummy_system_default) params.hardware_info = dummy_system; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1500,16 +1525,19 @@ TEST(TestComponentInterfaces, dummy_system_default) EXPECT_EQ(hardware_interface::return_type::OK, system_hw.perform_command_mode_switch({}, {})); } -TEST(TestComponentInterfaces, dummy_command_mode_system) +TEST_F(TestComponentInterfaces, dummy_command_mode_system) { hardware_interface::System system_hw( std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1537,16 +1565,18 @@ TEST(TestComponentInterfaces, dummy_command_mode_system) } // BEGIN (Handle export change): for backward compatibility -TEST(TestComponentInterfaces, dummy_actuator_read_error_behavior) +TEST_F(TestComponentInterfaces, dummy_actuator_read_error_behavior) { hardware_interface::Actuator actuator_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_actuator_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1602,7 +1632,7 @@ TEST(TestComponentInterfaces, dummy_actuator_read_error_behavior) } // END -TEST(TestComponentInterfaces, dummy_actuator_default_read_error_behavior) +TEST_F(TestComponentInterfaces, dummy_actuator_default_read_error_behavior) { hardware_interface::Actuator actuator_hw( std::make_unique()); @@ -1619,6 +1649,7 @@ TEST(TestComponentInterfaces, dummy_actuator_default_read_error_behavior) params.hardware_info = dummy_actuator; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); @@ -1678,16 +1709,18 @@ TEST(TestComponentInterfaces, dummy_actuator_default_read_error_behavior) } // BEGIN (Handle export change): for backward compatibility -TEST(TestComponentInterfaces, dummy_actuator_write_error_behavior) +TEST_F(TestComponentInterfaces, dummy_actuator_write_error_behavior) { hardware_interface::Actuator actuator_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_actuator_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1743,7 +1776,7 @@ TEST(TestComponentInterfaces, dummy_actuator_write_error_behavior) } // END -TEST(TestComponentInterfaces, dummy_actuator_default_write_error_behavior) +TEST_F(TestComponentInterfaces, dummy_actuator_default_write_error_behavior) { hardware_interface::Actuator actuator_hw( std::make_unique()); @@ -1760,6 +1793,7 @@ TEST(TestComponentInterfaces, dummy_actuator_default_write_error_behavior) params.hardware_info = dummy_actuator; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1818,16 +1852,18 @@ TEST(TestComponentInterfaces, dummy_actuator_default_write_error_behavior) } // BEGIN (Handle export change): for backward compatibility -TEST(TestComponentInterfaces, dummy_sensor_read_error_behavior) +TEST_F(TestComponentInterfaces, dummy_sensor_read_error_behavior) { hardware_interface::Sensor sensor_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_sensor_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = sensor_hw.initialize(params); auto state_interfaces = sensor_hw.export_state_interfaces(); @@ -1888,7 +1924,7 @@ TEST(TestComponentInterfaces, dummy_sensor_read_error_behavior) } // END -TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior) +TEST_F(TestComponentInterfaces, dummy_sensor_default_read_error_behavior) { hardware_interface::Sensor sensor_hw(std::make_unique()); @@ -1904,6 +1940,7 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior) params.hardware_info = voltage_sensor_res; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = sensor_hw.initialize(params); auto state_interfaces = sensor_hw.export_state_interfaces(); @@ -1953,16 +1990,18 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior) } // BEGIN (Handle export change): for backward compatibility -TEST(TestComponentInterfaces, dummy_system_read_error_behavior) +TEST_F(TestComponentInterfaces, dummy_system_read_error_behavior) { hardware_interface::System system_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -2023,7 +2062,7 @@ TEST(TestComponentInterfaces, dummy_system_read_error_behavior) } // END -TEST(TestComponentInterfaces, dummy_system_default_read_error_behavior) +TEST_F(TestComponentInterfaces, dummy_system_default_read_error_behavior) { hardware_interface::System system_hw(std::make_unique()); @@ -2039,6 +2078,7 @@ TEST(TestComponentInterfaces, dummy_system_default_read_error_behavior) params.hardware_info = dummy_system; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -2099,16 +2139,18 @@ TEST(TestComponentInterfaces, dummy_system_default_read_error_behavior) } // BEGIN (Handle export change): for backward compatibility -TEST(TestComponentInterfaces, dummy_system_write_error_behavior) +TEST_F(TestComponentInterfaces, dummy_system_write_error_behavior) { hardware_interface::System system_hw(std::make_unique()); - hardware_interface::HardwareInfo mock_hw_info{}; + hardware_interface::HardwareInfo mock_hw_info; + mock_hw_info.name = "mock_hw"; rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); hardware_interface::HardwareComponentParams params; params.hardware_info = mock_hw_info; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -2169,7 +2211,7 @@ TEST(TestComponentInterfaces, dummy_system_write_error_behavior) } // END -TEST(TestComponentInterfaces, dummy_system_default_write_error_behavior) +TEST_F(TestComponentInterfaces, dummy_system_default_write_error_behavior) { hardware_interface::System system_hw(std::make_unique()); @@ -2185,6 +2227,7 @@ TEST(TestComponentInterfaces, dummy_system_default_write_error_behavior) params.hardware_info = dummy_system; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); diff --git a/hardware_interface/test/test_component_interfaces_custom_export.cpp b/hardware_interface/test/test_component_interfaces_custom_export.cpp index 80e9ab83f9..428f447b1e 100644 --- a/hardware_interface/test/test_component_interfaces_custom_export.cpp +++ b/hardware_interface/test/test_component_interfaces_custom_export.cpp @@ -32,6 +32,7 @@ #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "hardware_interface/types/lifecycle_state_names.hpp" #include "lifecycle_msgs/msg/state.hpp" +#include "rclcpp/executors/multi_threaded_executor.hpp" #include "rclcpp/node.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "ros2_control_test_assets/components_urdfs.hpp" @@ -150,8 +151,22 @@ class DummySystemDefault : public hardware_interface::SystemInterface }; } // namespace test_components +class TestComponentInterfaces : public ::testing::Test +{ +protected: + void SetUp() override + { + if (!rclcpp::ok()) + { + rclcpp::init(0, nullptr); + } + executor_ = std::make_shared(); + } -TEST(TestComponentInterfaces, dummy_actuator_default_custom_export) + void TearDown() override { rclcpp::shutdown(); } + std::shared_ptr executor_; +}; +TEST_F(TestComponentInterfaces, dummy_actuator_default_custom_export) { hardware_interface::Actuator actuator_hw( std::make_unique()); @@ -167,6 +182,7 @@ TEST(TestComponentInterfaces, dummy_actuator_default_custom_export) params.hardware_info = dummy_actuator; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = actuator_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); @@ -220,7 +236,7 @@ TEST(TestComponentInterfaces, dummy_actuator_default_custom_export) } } -TEST(TestComponentInterfaces, dummy_sensor_default_custom_export) +TEST_F(TestComponentInterfaces, dummy_sensor_default_custom_export) { hardware_interface::Sensor sensor_hw(std::make_unique()); @@ -236,6 +252,7 @@ TEST(TestComponentInterfaces, dummy_sensor_default_custom_export) params.hardware_info = voltage_sensor_res; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = sensor_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -260,7 +277,7 @@ TEST(TestComponentInterfaces, dummy_sensor_default_custom_export) } } -TEST(TestComponentInterfaces, dummy_system_default_custom_export) +TEST_F(TestComponentInterfaces, dummy_system_default_custom_export) { hardware_interface::System system_hw(std::make_unique()); @@ -276,6 +293,7 @@ TEST(TestComponentInterfaces, dummy_system_default_custom_export) params.hardware_info = dummy_system; params.clock = node->get_clock(); params.logger = node->get_logger(); + params.executor = executor_; auto state = system_hw.initialize(params); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); From 63e2902493480aac43f737ff14ce77e4095e8277 Mon Sep 17 00:00:00 2001 From: Soham Patil Date: Fri, 24 Oct 2025 14:07:22 +0000 Subject: [PATCH 4/4] added nullptr --- hardware_interface/test/test_component_interfaces.cpp | 3 +-- .../test/test_component_interfaces_custom_export.cpp | 3 +-- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/hardware_interface/test/test_component_interfaces.cpp b/hardware_interface/test/test_component_interfaces.cpp index 75e445d3f7..149f79508f 100644 --- a/hardware_interface/test/test_component_interfaces.cpp +++ b/hardware_interface/test/test_component_interfaces.cpp @@ -788,11 +788,10 @@ class TestComponentInterfaces : public ::testing::Test { rclcpp::init(0, nullptr); } - executor_ = std::make_shared(); } void TearDown() override { rclcpp::shutdown(); } - std::shared_ptr executor_; + std::shared_ptr executor_ = nullptr; }; // BEGIN (Handle export change): for backward compatibility TEST_F(TestComponentInterfaces, dummy_actuator) diff --git a/hardware_interface/test/test_component_interfaces_custom_export.cpp b/hardware_interface/test/test_component_interfaces_custom_export.cpp index 428f447b1e..f2ff2925e7 100644 --- a/hardware_interface/test/test_component_interfaces_custom_export.cpp +++ b/hardware_interface/test/test_component_interfaces_custom_export.cpp @@ -160,11 +160,10 @@ class TestComponentInterfaces : public ::testing::Test { rclcpp::init(0, nullptr); } - executor_ = std::make_shared(); } void TearDown() override { rclcpp::shutdown(); } - std::shared_ptr executor_; + std::shared_ptr executor_ = nullptr; }; TEST_F(TestComponentInterfaces, dummy_actuator_default_custom_export) {