@@ -518,6 +518,46 @@ class TestGenericSystem : public ::testing::Test
518518 </ros2_control>
519519)" ;
520520
521+ valid_hardware_system_2dof_standard_interfaces_with_different_control_modes_ =
522+ R"(
523+ <ros2_control name="HardwareSystem2dofStandardInterfacesWithDifferentControlModes" type="system">
524+ <hardware>
525+ <plugin>mock_components/GenericSystem</plugin>
526+ <param name="calculate_dynamics">true</param>
527+ </hardware>
528+ <joint name="joint1">
529+ <command_interface name="position"/>
530+ <state_interface name="position">
531+ <param name="initial_value">3.45</param>
532+ </state_interface>
533+ <state_interface name="velocity"/>
534+ <state_interface name="acceleration"/>
535+ </joint>
536+ <joint name="joint2">
537+ <command_interface name="velocity"/>
538+ <state_interface name="position">
539+ <param name="initial_value">2.78</param>
540+ </state_interface>
541+ <state_interface name="position"/>
542+ <state_interface name="velocity"/>
543+ <state_interface name="acceleration"/>
544+ </joint>
545+ <joint name="joint3">
546+ <command_interface name="acceleration"/>
547+ <state_interface name="position">
548+ <param name="initial_value">2.78</param>
549+ </state_interface>
550+ <state_interface name="position"/>
551+ <state_interface name="velocity"/>
552+ <state_interface name="acceleration"/>
553+ </joint>
554+ <gpio name="flange_vacuum">
555+ <command_interface name="vacuum"/>
556+ <state_interface name="vacuum" data_type="double"/>
557+ </gpio>
558+ </ros2_control>
559+ )" ;
560+
521561 disabled_commands_ =
522562 R"(
523563 <ros2_control name="GenericSystem2dof" type="system">
@@ -556,6 +596,7 @@ class TestGenericSystem : public ::testing::Test
556596 std::string sensor_with_initial_value_;
557597 std::string gpio_with_initial_value_;
558598 std::string hardware_system_2dof_standard_interfaces_with_different_control_modes_;
599+ std::string valid_hardware_system_2dof_standard_interfaces_with_different_control_modes_;
559600 std::string disabled_commands_;
560601};
561602
@@ -1901,3 +1942,43 @@ TEST_F(TestGenericSystem, disabled_commands_flag_is_active)
19011942 ASSERT_EQ (0.0 , j1v_s.get_value ());
19021943 ASSERT_EQ (0.11 , j1p_c.get_value ());
19031944}
1945+
1946+ TEST_F (TestGenericSystem, prepare_command_mode_switch_works_with_all_example_tags)
1947+ {
1948+ auto check_prepare_command_mode_switch = [&](const std::string & urdf)
1949+ {
1950+ TestableResourceManager rm (
1951+ ros2_control_test_assets::urdf_head + urdf + ros2_control_test_assets::urdf_tail);
1952+ auto start_interfaces = rm.command_interface_keys ();
1953+ std::vector<std::string> stop_interfaces;
1954+ return rm.prepare_command_mode_switch (start_interfaces, stop_interfaces);
1955+ };
1956+
1957+ ASSERT_TRUE (check_prepare_command_mode_switch (hardware_system_2dof_));
1958+ ASSERT_TRUE (check_prepare_command_mode_switch (hardware_system_2dof_asymetric_));
1959+ ASSERT_TRUE (check_prepare_command_mode_switch (hardware_system_2dof_standard_interfaces_));
1960+ ASSERT_TRUE (check_prepare_command_mode_switch (hardware_system_2dof_with_other_interface_));
1961+ ASSERT_TRUE (check_prepare_command_mode_switch (hardware_system_2dof_with_sensor_));
1962+ ASSERT_TRUE (check_prepare_command_mode_switch (hardware_system_2dof_with_sensor_mock_command_));
1963+ ASSERT_TRUE (
1964+ check_prepare_command_mode_switch (hardware_system_2dof_with_sensor_mock_command_True_));
1965+ ASSERT_TRUE (check_prepare_command_mode_switch (hardware_system_2dof_with_mimic_joint_));
1966+ ASSERT_TRUE (
1967+ check_prepare_command_mode_switch (hardware_system_2dof_standard_interfaces_with_offset_));
1968+ ASSERT_TRUE (check_prepare_command_mode_switch (
1969+ hardware_system_2dof_standard_interfaces_with_custom_interface_for_offset_));
1970+ ASSERT_TRUE (check_prepare_command_mode_switch (
1971+ hardware_system_2dof_standard_interfaces_with_custom_interface_for_offset_missing_));
1972+ ASSERT_TRUE (check_prepare_command_mode_switch (valid_urdf_ros2_control_system_robot_with_gpio_));
1973+ ASSERT_TRUE (check_prepare_command_mode_switch (
1974+ valid_urdf_ros2_control_system_robot_with_gpio_mock_command_));
1975+ ASSERT_TRUE (check_prepare_command_mode_switch (
1976+ valid_urdf_ros2_control_system_robot_with_gpio_mock_command_True_));
1977+ ASSERT_TRUE (check_prepare_command_mode_switch (sensor_with_initial_value_));
1978+ ASSERT_TRUE (check_prepare_command_mode_switch (gpio_with_initial_value_));
1979+ ASSERT_FALSE (check_prepare_command_mode_switch (
1980+ hardware_system_2dof_standard_interfaces_with_different_control_modes_));
1981+ ASSERT_TRUE (check_prepare_command_mode_switch (
1982+ valid_hardware_system_2dof_standard_interfaces_with_different_control_modes_));
1983+ ASSERT_TRUE (check_prepare_command_mode_switch (disabled_commands_));
1984+ }
0 commit comments