diff --git a/hardware_interface/doc/mock_components_userdoc.rst b/hardware_interface/doc/mock_components_userdoc.rst index 7e5a997a21..5663fd0350 100644 --- a/hardware_interface/doc/mock_components_userdoc.rst +++ b/hardware_interface/doc/mock_components_userdoc.rst @@ -22,6 +22,7 @@ Features: - support for mimic joints, which is parsed from the URDF (see the `URDF wiki `__) - mirroring commands to states with and without offset - fake command interfaces for setting sensor data from an external node (combined with a :ref:`forward controller `) + - fake gpio interfaces for setting sensor data from an external node (combined with a :ref:`forward controller `) Parameters @@ -36,6 +37,10 @@ mock_sensor_commands (optional; boolean; default: false) Creates fake command interfaces for faking sensor measurements with an external command. Those interfaces are usually used by a :ref:`forward controller ` to provide access from ROS-world. +mock_gpio_commands (optional; boolean; default: false) + Creates fake command interfaces for faking GPIO states with an external command. + Those interfaces are usually used by a :ref:`forward controller ` to provide access from ROS-world. + position_state_following_offset (optional; double; default: 0.0) Following offset added to the commanded values when mirrored to states. diff --git a/hardware_interface/src/mock_components/generic_system.cpp b/hardware_interface/src/mock_components/generic_system.cpp index 5e5165e34f..2d8a01a34f 100644 --- a/hardware_interface/src/mock_components/generic_system.cpp +++ b/hardware_interface/src/mock_components/generic_system.cpp @@ -598,13 +598,13 @@ return_type GenericSystem::read(const rclcpp::Time & /*time*/, const rclcpp::Dur mirror_command_to_state(sensor_states_, sensor_mock_commands_); } - // do loopback on all gpio interfaces if (use_mock_gpio_command_interfaces_) { mirror_command_to_state(gpio_states_, gpio_mock_commands_); } else { + // do loopback on all gpio interfaces mirror_command_to_state(gpio_states_, gpio_commands_); }