@@ -483,6 +483,24 @@ class TestGenericSystem : public ::testing::Test
483483 </gpio>
484484 </ros2_control>
485485)" ;
486+
487+ disabled_commands_ =
488+ R"(
489+ <ros2_control name="GenericSystem2dof" type="system">
490+ <hardware>
491+ <plugin>fake_components/GenericSystem</plugin>
492+ <param name="disable_commands">True</param>
493+ </hardware>
494+ <joint name="joint1">
495+ <command_interface name="position"/>
496+ <command_interface name="velocity"/>
497+ <state_interface name="position">
498+ <param name="initial_value">3.45</param>
499+ </state_interface>
500+ <state_interface name="velocity"/>
501+ </joint>
502+ </ros2_control>
503+ )" ;
486504 }
487505
488506 std::string hardware_robot_2dof_;
@@ -503,6 +521,7 @@ class TestGenericSystem : public ::testing::Test
503521 std::string valid_urdf_ros2_control_system_robot_with_gpio_mock_command_True_;
504522 std::string sensor_with_initial_value_;
505523 std::string gpio_with_initial_value_;
524+ std::string disabled_commands_;
506525};
507526
508527// Forward declaration
@@ -1604,3 +1623,51 @@ TEST_F(TestGenericSystem, gpio_with_initial_value)
16041623
16051624 ASSERT_EQ (1 , state.get_value ());
16061625}
1626+
1627+ TEST_F (TestGenericSystem, disabled_commands_flag_is_active)
1628+ {
1629+ auto urdf =
1630+ ros2_control_test_assets::urdf_head + disabled_commands_ + ros2_control_test_assets::urdf_tail;
1631+ TestableResourceManager rm (urdf);
1632+ // Activate components to get all interfaces available
1633+ activate_components (rm);
1634+
1635+ // Check interfaces
1636+ EXPECT_EQ (1u , rm.system_components_size ());
1637+ ASSERT_EQ (2u , rm.state_interface_keys ().size ());
1638+ EXPECT_TRUE (rm.state_interface_exists (" joint1/position" ));
1639+ EXPECT_TRUE (rm.state_interface_exists (" joint1/velocity" ));
1640+
1641+ ASSERT_EQ (2u , rm.command_interface_keys ().size ());
1642+ EXPECT_TRUE (rm.command_interface_exists (" joint1/position" ));
1643+ EXPECT_TRUE (rm.command_interface_exists (" joint1/velocity" ));
1644+
1645+ // Check initial values
1646+ hardware_interface::LoanedStateInterface j1p_s = rm.claim_state_interface (" joint1/position" );
1647+ hardware_interface::LoanedStateInterface j1v_s = rm.claim_state_interface (" joint1/velocity" );
1648+ hardware_interface::LoanedCommandInterface j1p_c = rm.claim_command_interface (" joint1/position" );
1649+
1650+ ASSERT_EQ (3.45 , j1p_s.get_value ());
1651+ ASSERT_EQ (0.0 , j1v_s.get_value ());
1652+ ASSERT_TRUE (std::isnan (j1p_c.get_value ()));
1653+
1654+ // set some new values in commands
1655+ j1p_c.set_value (0.11 );
1656+
1657+ // State values should not be changed
1658+ ASSERT_EQ (3.45 , j1p_s.get_value ());
1659+ ASSERT_EQ (0.0 , j1v_s.get_value ());
1660+ ASSERT_EQ (0.11 , j1p_c.get_value ());
1661+
1662+ // write() does not change values
1663+ rm.write (TIME, PERIOD);
1664+ ASSERT_EQ (3.45 , j1p_s.get_value ());
1665+ ASSERT_EQ (0.0 , j1v_s.get_value ());
1666+ ASSERT_EQ (0.11 , j1p_c.get_value ());
1667+
1668+ // read() also does not change values
1669+ rm.read (TIME, PERIOD);
1670+ ASSERT_EQ (3.45 , j1p_s.get_value ());
1671+ ASSERT_EQ (0.0 , j1v_s.get_value ());
1672+ ASSERT_EQ (0.11 , j1p_c.get_value ());
1673+ }
0 commit comments