From 8848424c0fef456d36a24c66dc953d948207a06b Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Fri, 20 Dec 2024 21:42:39 +0100 Subject: [PATCH] Add asynchronous hardware components documentation (#1961) --- .../doc/asynchronous_components.rst | 99 +++++++++++++++++++ .../doc/hardware_components_userdoc.rst | 1 + 2 files changed, 100 insertions(+) create mode 100644 hardware_interface/doc/asynchronous_components.rst diff --git a/hardware_interface/doc/asynchronous_components.rst b/hardware_interface/doc/asynchronous_components.rst new file mode 100644 index 0000000000..c73281c3fe --- /dev/null +++ b/hardware_interface/doc/asynchronous_components.rst @@ -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 `) as follows + +For a RRBot with multimodal gripper and external sensor: + +.. code-block:: xml + + + + ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware + 2.0 + 3.0 + 2.0 + + + + -1 + 1 + + + + + + -1 + 1 + + + + + + + + + + + + + + + ros2_control_demo_hardware/MultimodalGripper + + + + 0 + 100 + + + + + + + ros2_control_demo_hardware/ForceTorqueSensor2DHardware + 0.43 + + + + + kuka_tcp + 100 + 100 + + + + + + + + + + +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. diff --git a/hardware_interface/doc/hardware_components_userdoc.rst b/hardware_interface/doc/hardware_components_userdoc.rst index 0a980cad4e..3870433ef0 100644 --- a/hardware_interface/doc/hardware_components_userdoc.rst +++ b/hardware_interface/doc/hardware_components_userdoc.rst @@ -17,6 +17,7 @@ Guidelines and Best Practices Hardware Interface Types Writing a Hardware Component Different Update Rates + Asynchronous Execution Handling of errors that happen during read() and write() calls