Skip to content

Commit bc8052a

Browse files
authored
[MockHardware] Enable disabling of command to simulate HW failures. (#1027)
1 parent e89fbe7 commit bc8052a

File tree

4 files changed

+93
-0
lines changed

4 files changed

+93
-0
lines changed

hardware_interface/doc/mock_components_userdoc.rst

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,11 @@ Features:
2727
Parameters
2828
,,,,,,,,,,
2929

30+
disable_commands (optional; boolean; default: false)
31+
Disables mirroring commands to states.
32+
This option is helpful to simulate an erroneous connection to the hardware when nothing breaks, but suddenly there is no feedback from a hardware interface.
33+
Or it can help you to test your setup when the hardware is running without feedback, i.e., in open loop configuration.
34+
3035
mock_sensor_commands (optional; boolean; default: false)
3136
Creates fake command interfaces for faking sensor measurements with an external command.
3237
Those interfaces are usually used by a :ref:`forward controller <forward_command_controller_userdoc>` to provide access from ROS-world.

hardware_interface/include/mock_components/generic_system.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -114,6 +114,8 @@ class HARDWARE_INTERFACE_PUBLIC GenericSystem : public hardware_interface::Syste
114114
double position_state_following_offset_;
115115
std::string custom_interface_with_following_offset_;
116116
size_t index_custom_interface_with_following_offset_;
117+
118+
bool command_propagation_disabled_;
117119
};
118120

119121
typedef GenericSystem GenericRobot;

hardware_interface/src/mock_components/generic_system.cpp

Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -119,6 +119,18 @@ CallbackReturn GenericSystem::on_init(const hardware_interface::HardwareInfo & i
119119
}
120120
}
121121

122+
// check if there is parameter that disables commands
123+
// this way we simulate disconnected driver
124+
it = info_.hardware_parameters.find("disable_commands");
125+
if (it != info.hardware_parameters.end())
126+
{
127+
command_propagation_disabled_ = hardware_interface::parse_bool(it->second);
128+
}
129+
else
130+
{
131+
command_propagation_disabled_ = false;
132+
}
133+
122134
// process parameters about state following
123135
position_state_following_offset_ = 0.0;
124136
custom_interface_with_following_offset_ = "";
@@ -359,6 +371,13 @@ std::vector<hardware_interface::CommandInterface> GenericSystem::export_command_
359371

360372
return_type GenericSystem::read(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
361373
{
374+
if (command_propagation_disabled_)
375+
{
376+
RCUTILS_LOG_WARN_NAMED(
377+
"mock_generic_system", "Command propagation is disabled - no values will be returned!");
378+
return return_type::OK;
379+
}
380+
362381
auto mirror_command_to_state = [](auto & states_, auto commands_, size_t start_index = 0)
363382
{
364383
for (size_t i = start_index; i < states_.size(); ++i)

hardware_interface/test/mock_components/test_generic_system.cpp

Lines changed: 67 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -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

Comments
 (0)