diff --git a/hardware_interface/test/mock_components/test_generic_system.cpp b/hardware_interface/test/mock_components/test_generic_system.cpp index fb8f04b269f..0eb68d20527 100644 --- a/hardware_interface/test/mock_components/test_generic_system.cpp +++ b/hardware_interface/test/mock_components/test_generic_system.cpp @@ -69,7 +69,7 @@ class TestGenericSystem : public ::testing::Test hardware_system_2dof_ = R"( - + mock_components/GenericSystem @@ -88,7 +88,7 @@ class TestGenericSystem : public ::testing::Test hardware_system_2dof_asymetric_ = R"( - + mock_components/GenericSystem @@ -108,7 +108,7 @@ class TestGenericSystem : public ::testing::Test hardware_system_2dof_standard_interfaces_ = R"( - + mock_components/GenericSystem @@ -131,7 +131,7 @@ class TestGenericSystem : public ::testing::Test hardware_system_2dof_with_other_interface_ = R"( - + mock_components/GenericSystem @@ -161,7 +161,7 @@ class TestGenericSystem : public ::testing::Test hardware_system_2dof_with_sensor_ = R"( - + mock_components/GenericSystem @@ -189,7 +189,7 @@ class TestGenericSystem : public ::testing::Test hardware_system_2dof_with_sensor_mock_command_ = R"( - + mock_components/GenericSystem true @@ -218,7 +218,7 @@ class TestGenericSystem : public ::testing::Test hardware_system_2dof_with_sensor_mock_command_True_ = R"( - + mock_components/GenericSystem True @@ -247,7 +247,7 @@ class TestGenericSystem : public ::testing::Test hardware_system_2dof_with_mimic_joint_ = R"( - + mock_components/GenericSystem @@ -271,7 +271,7 @@ class TestGenericSystem : public ::testing::Test hardware_system_2dof_standard_interfaces_with_offset_ = R"( - + mock_components/GenericSystem -3 @@ -297,7 +297,7 @@ class TestGenericSystem : public ::testing::Test hardware_system_2dof_standard_interfaces_with_custom_interface_for_offset_missing_ = R"( - + mock_components/GenericSystem -3 @@ -322,7 +322,7 @@ class TestGenericSystem : public ::testing::Test hardware_system_2dof_standard_interfaces_with_custom_interface_for_offset_ = R"( - + mock_components/GenericSystem -3 @@ -349,7 +349,7 @@ class TestGenericSystem : public ::testing::Test valid_urdf_ros2_control_system_robot_with_gpio_ = R"( - + mock_components/GenericSystem 2 @@ -385,7 +385,7 @@ class TestGenericSystem : public ::testing::Test valid_urdf_ros2_control_system_robot_with_gpio_mock_command_ = R"( - + mock_components/GenericSystem true @@ -419,7 +419,7 @@ class TestGenericSystem : public ::testing::Test valid_urdf_ros2_control_system_robot_with_gpio_mock_command_True_ = R"( - + mock_components/GenericSystem True @@ -453,7 +453,7 @@ class TestGenericSystem : public ::testing::Test sensor_with_initial_value_ = R"( - + fake_components/GenericSystem @@ -473,7 +473,7 @@ class TestGenericSystem : public ::testing::Test gpio_with_initial_value_ = R"( - + fake_components/GenericSystem @@ -487,7 +487,7 @@ class TestGenericSystem : public ::testing::Test hardware_system_2dof_standard_interfaces_with_different_control_modes_ = R"( - + mock_components/GenericSystem true @@ -520,7 +520,7 @@ class TestGenericSystem : public ::testing::Test valid_hardware_system_2dof_standard_interfaces_with_different_control_modes_ = R"( - + mock_components/GenericSystem true @@ -560,7 +560,7 @@ class TestGenericSystem : public ::testing::Test disabled_commands_ = R"( - + fake_components/GenericSystem True @@ -714,7 +714,7 @@ TEST_F(TestGenericSystem, generic_system_2dof_symetric_interfaces) ros2_control_test_assets::urdf_tail; TestableResourceManager rm(urdf); // Activate components to get all interfaces available - activate_components(rm, {"MockHardwareSystem"}); + activate_components(rm); // Check interfaces EXPECT_EQ(1u, rm.system_components_size()); @@ -745,7 +745,7 @@ TEST_F(TestGenericSystem, generic_system_2dof_asymetric_interfaces) ros2_control_test_assets::urdf_tail; TestableResourceManager rm(urdf); // Activate components to get all interfaces available - activate_components(rm, {"MockHardwareSystem"}); + activate_components(rm); // Check interfaces EXPECT_EQ(1u, rm.system_components_size()); @@ -892,7 +892,7 @@ TEST_F(TestGenericSystem, generic_system_2dof_functionality) auto urdf = ros2_control_test_assets::urdf_head + hardware_system_2dof_standard_interfaces_ + ros2_control_test_assets::urdf_tail; - generic_system_functional_test(urdf, {"MockHardwareSystem"}); + generic_system_functional_test(urdf); } TEST_F(TestGenericSystem, generic_system_2dof_other_interfaces) @@ -901,7 +901,7 @@ TEST_F(TestGenericSystem, generic_system_2dof_other_interfaces) ros2_control_test_assets::urdf_tail; TestableResourceManager rm(urdf); // Activate components to get all interfaces available - activate_components(rm, {"MockHardwareSystem"}); + activate_components(rm); // Check interfaces EXPECT_EQ(1u, rm.system_components_size()); @@ -984,7 +984,7 @@ TEST_F(TestGenericSystem, generic_system_2dof_sensor) ros2_control_test_assets::urdf_tail; TestableResourceManager rm(urdf); // Activate components to get all interfaces available - activate_components(rm, {"MockHardwareSystem"}); + activate_components(rm); // Check interfaces EXPECT_EQ(1u, rm.system_components_size()); @@ -1205,7 +1205,7 @@ TEST_F(TestGenericSystem, generic_system_2dof_sensor_mock_command) auto urdf = ros2_control_test_assets::urdf_head + hardware_system_2dof_with_sensor_mock_command_ + ros2_control_test_assets::urdf_tail; - test_generic_system_with_mock_sensor_commands(urdf, "MockHardwareSystem"); + test_generic_system_with_mock_sensor_commands(urdf, "GenericSystem2dof"); } TEST_F(TestGenericSystem, generic_system_2dof_sensor_mock_command_True) @@ -1214,7 +1214,7 @@ TEST_F(TestGenericSystem, generic_system_2dof_sensor_mock_command_True) hardware_system_2dof_with_sensor_mock_command_True_ + ros2_control_test_assets::urdf_tail; - test_generic_system_with_mock_sensor_commands(urdf, "MockHardwareSystem"); + test_generic_system_with_mock_sensor_commands(urdf, "GenericSystem2dof"); } void TestGenericSystem::test_generic_system_with_mimic_joint(const std::string & urdf) @@ -1288,7 +1288,7 @@ TEST_F(TestGenericSystem, hardware_system_2dof_with_mimic_joint) auto urdf = ros2_control_test_assets::urdf_head + hardware_system_2dof_with_mimic_joint_ + ros2_control_test_assets::urdf_tail; - test_generic_system_with_mimic_joint(urdf, "MockHardwareSystem"); + test_generic_system_with_mimic_joint(urdf, "GenericSystem2dof"); } TEST_F(TestGenericSystem, generic_system_2dof_functionality_with_offset) @@ -1297,7 +1297,7 @@ TEST_F(TestGenericSystem, generic_system_2dof_functionality_with_offset) hardware_system_2dof_standard_interfaces_with_offset_ + ros2_control_test_assets::urdf_tail; - generic_system_functional_test(urdf, "MockHardwareSystem", -3); + generic_system_functional_test(urdf, -3); } TEST_F(TestGenericSystem, generic_system_2dof_functionality_with_offset_custom_interface_missing) @@ -1307,7 +1307,7 @@ TEST_F(TestGenericSystem, generic_system_2dof_functionality_with_offset_custom_i ros2_control_test_assets::urdf_tail; // custom interface is missing so offset will not be applied - generic_system_functional_test(urdf, "MockHardwareSystem", 0.0); + generic_system_functional_test(urdf, 0.0); } TEST_F(TestGenericSystem, generic_system_2dof_functionality_with_offset_custom_interface) @@ -1320,7 +1320,7 @@ TEST_F(TestGenericSystem, generic_system_2dof_functionality_with_offset_custom_i TestableResourceManager rm(urdf); - const std::string hardware_name = "MockHardwareSystem"; + const std::string hardware_name = "GenericSystem2dof"; // check is hardware is configured auto status_map = rm.get_components_status(); @@ -1436,7 +1436,7 @@ TEST_F(TestGenericSystem, valid_urdf_ros2_control_system_robot_with_gpio) valid_urdf_ros2_control_system_robot_with_gpio_ + ros2_control_test_assets::urdf_tail; TestableResourceManager rm(urdf); - const std::string hardware_name = "MockHardwareSystem"; + const std::string hardware_name = "GenericSystem2dof"; // check is hardware is started auto status_map = rm.get_components_status(); @@ -1644,7 +1644,7 @@ TEST_F(TestGenericSystem, valid_urdf_ros2_control_system_robot_with_gpio_mock_co valid_urdf_ros2_control_system_robot_with_gpio_mock_command_ + ros2_control_test_assets::urdf_tail; - test_generic_system_with_mock_gpio_commands(urdf, "MockHardwareSystem"); + test_generic_system_with_mock_gpio_commands(urdf, "GenericSystem2dof"); } TEST_F(TestGenericSystem, valid_urdf_ros2_control_system_robot_with_gpio_mock_command_True) @@ -1653,7 +1653,7 @@ TEST_F(TestGenericSystem, valid_urdf_ros2_control_system_robot_with_gpio_mock_co valid_urdf_ros2_control_system_robot_with_gpio_mock_command_True_ + ros2_control_test_assets::urdf_tail; - test_generic_system_with_mock_gpio_commands(urdf, "MockHardwareSystem"); + test_generic_system_with_mock_gpio_commands(urdf, "GenericSystem2dof"); } TEST_F(TestGenericSystem, sensor_with_initial_value) @@ -1662,7 +1662,7 @@ TEST_F(TestGenericSystem, sensor_with_initial_value) ros2_control_test_assets::urdf_tail; TestableResourceManager rm(urdf); // Activate components to get all interfaces available - activate_components(rm, {"MockHardwareSystem"}); + activate_components(rm); // Check interfaces EXPECT_EQ(1u, rm.system_components_size()); @@ -1690,7 +1690,7 @@ TEST_F(TestGenericSystem, gpio_with_initial_value) ros2_control_test_assets::urdf_tail; TestableResourceManager rm(urdf); // Activate components to get all interfaces available - activate_components(rm, {"MockHardwareSystem"}); + activate_components(rm); // Check interfaces EXPECT_EQ(1u, rm.system_components_size()); @@ -1711,7 +1711,7 @@ TEST_F(TestGenericSystem, simple_dynamics_pos_vel_acc_control_modes_interfaces) TestableResourceManager rm(urdf); // Activate components to get all interfaces available - activate_components(rm, {"MockHardwareSystem"}); + activate_components(rm); // Check interfaces EXPECT_EQ(1u, rm.system_components_size()); @@ -1905,7 +1905,7 @@ TEST_F(TestGenericSystem, disabled_commands_flag_is_active) ros2_control_test_assets::urdf_head + disabled_commands_ + ros2_control_test_assets::urdf_tail; TestableResourceManager rm(urdf); // Activate components to get all interfaces available - activate_components(rm, {"MockHardwareSystem"}); + activate_components(rm); // Check interfaces EXPECT_EQ(1u, rm.system_components_size()); @@ -1953,7 +1953,7 @@ TEST_F(TestGenericSystem, prepare_command_mode_switch_works_with_all_example_tag TestableResourceManager rm( ros2_control_test_assets::urdf_head + urdf + ros2_control_test_assets::urdf_tail); rclcpp_lifecycle::State state(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, "active"); - rm.set_component_state("MockHardwareSystem", state); + rm.set_component_state("GenericSystem2dof", state); auto start_interfaces = rm.command_interface_keys(); std::vector stop_interfaces; return rm.prepare_command_mode_switch(start_interfaces, stop_interfaces);