Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add asynchronous hardware components documentation #1961

Merged
Merged
Show file tree
Hide file tree
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions doc/release_notes.rst
Original file line number Diff line number Diff line change
Expand Up @@ -158,6 +158,7 @@ hardware_interface
* With (`#1421 <https://github.com/ros-controls/ros2_control/pull/1421>`_) a key-value storage is added to InterfaceInfo. This allows to define extra params with per Command-/StateInterface in the ``.ros2_control.xacro`` file.
* With (`#1763 <https://github.com/ros-controls/ros2_control/pull/1763>`_) parsing for SDF published to ``robot_description`` topic is now also supported.
* With (`#1567 <https://github.com/ros-controls/ros2_control/pull/1567>`_) all the Hardware components now have a fully functional asynchronous functionality, by simply adding ``is_async`` tag to the ros2_control tag in the URDF. This will allow the hardware components to run in a separate thread, and the controller manager will be able to run the controllers in parallel with the hardware components.
* Add documentation for asynchronous hardware components (`#1961 <https://github.com/ros-controls/ros2_control/pull/1961>`_)
christophfroehlich marked this conversation as resolved.
Show resolved Hide resolved

joint_limits
************
Expand Down
99 changes: 99 additions & 0 deletions hardware_interface/doc/asynchronous_components.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
:github_url: https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/doc/different_update_rates_userdoc.rst

.. _asynchronous_components:

Running Hardware Components Asynchronously
============================================

The ``ros2_control`` framework allows to run hardware components asynchronously. This is useful when some of the hardware components need to run in a separate thread or executor. For example, a sensor takes longer to read data that affects the periodicity of the ``controller_manager`` control loop. In this case, the sensor can be run in a separate thread or executor to avoid blocking the control loop.

Parameters
-----------

The following parameters can be set in the ``ros2_control`` hardware configuration to run the hardware component asynchronously:

* ``is_async``: (optional) If set to ``true``, the hardware component will run asynchronously. Default is ``false``.
* ``thread_priority``: (optional) The priority of the thread that runs the hardware component. The priority is an integer value between 0 and 99. The default value is 50.

.. note::
The thread priority is only used when the hardware component is run asynchronously.
When the hardware component is run asynchronously, it uses the FIFO scheduling policy.

Examples
---------

The following examples show how to use the different hardware interface types synchronously and asynchronously with ``ros2_control`` URDF.
They can be combined together within the different hardware component types (system, actuator, sensor) (:ref:`see detailed documentation <overview_hardware_components>`) as follows

For a RRBot with multimodal gripper and external sensor:

.. code-block:: xml

<ros2_control name="RRBotSystemMutipleGPIOs" type="system">
<hardware>
<plugin>ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware</plugin>
<param name="example_param_hw_start_duration_sec">2.0</param>
<param name="example_param_hw_stop_duration_sec">3.0</param>
<param name="example_param_hw_slowdown">2.0</param>
</hardware>
<joint name="joint1">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
</joint>
<joint name="joint2">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
</joint>
<gpio name="flange_digital_IOs">
<command_interface name="digital_output1"/>
<state_interface name="digital_output1"/> <!-- Needed to know current state of the output -->
<command_interface name="digital_output2"/>
<state_interface name="digital_output2"/>
<state_interface name="digital_input1"/>
<state_interface name="digital_input2"/>
</gpio>
</ros2_control>
<ros2_control name="MultimodalGripper" type="actuator" is_async="true" thread_priority="30">
<hardware>
<plugin>ros2_control_demo_hardware/MultimodalGripper</plugin>
</hardware>
<joint name="parallel_fingers">
<command_interface name="position">
<param name="min">0</param>
<param name="max">100</param>
</command_interface>
<state_interface name="position"/>
</joint>
</ros2_control>
<ros2_control name="RRBotForceTorqueSensor2D" type="sensor" is_async="true">
<hardware>
<plugin>ros2_control_demo_hardware/ForceTorqueSensor2DHardware</plugin>
<param name="example_param_read_for_sec">0.43</param>
</hardware>
<sensor name="tcp_fts_sensor">
<state_interface name="fx"/>
<state_interface name="tz"/>
<param name="frame_id">kuka_tcp</param>
<param name="fx_range">100</param>
<param name="tz_range">100</param>
</sensor>
<sensor name="temp_feedback">
<state_interface name="temperature"/>
</sensor>
<gpio name="calibration">
<command_interface name="calibration_matrix_nr"/>
<state_interface name="calibration_matrix_nr"/>
</gpio>
</ros2_control>

In the above example, the following components are defined:

* A system hardware component named ``RRBotSystemMutipleGPIOs`` with two joints and a GPIO component that runs synchronously.
* An actuator hardware component named ``MultimodalGripper`` with a joint that runs asynchronously with a thread priority of 30.
* A sensor hardware component named ``RRBotForceTorqueSensor2D`` with two sensors and a GPIO component that runs asynchronously with the default thread priority of 50.
1 change: 1 addition & 0 deletions hardware_interface/doc/hardware_components_userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ Guidelines and Best Practices
Hardware Interface Types <hardware_interface_types_userdoc.rst>
Writing a Hardware Component <writing_new_hardware_component.rst>
Different Update Rates <different_update_rates_userdoc.rst>
Asynchronous Execution <asynchronous_components.rst>


Handling of errors that happen during read() and write() calls
Expand Down
Loading