From 1a81d0d0acd82f9327c07071ff0554d427110212 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Tue, 5 Sep 2023 16:57:49 +0000 Subject: [PATCH 1/3] Reformat hardware_components docs and add a empty page for hardware interface types --- .../doc/hardware_components_userdoc.rst | 32 ++++++++++++------- .../doc/hardware_interface_types_userdoc.rst | 6 ++++ ...rst => writing_new_hardware_component.rst} | 8 ++--- 3 files changed, 31 insertions(+), 15 deletions(-) create mode 100644 hardware_interface/doc/hardware_interface_types_userdoc.rst rename hardware_interface/doc/{writing_new_hardware_interface.rst => writing_new_hardware_component.rst} (98%) diff --git a/hardware_interface/doc/hardware_components_userdoc.rst b/hardware_interface/doc/hardware_components_userdoc.rst index cd93f472a5..1a8c5e611b 100644 --- a/hardware_interface/doc/hardware_components_userdoc.rst +++ b/hardware_interface/doc/hardware_components_userdoc.rst @@ -14,20 +14,21 @@ Guidelines and Best Practices .. toctree:: :titlesonly: - Writing a Hardware Interface + Hardware Interface Types + Writing a Hardware Component Handling of errors that happen during read() and write() calls ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -If ``hardware_interface::return_type::ERROR`` is returned from ``read()`` or ``write()`` methods of a hardware interface, ``on_error(previous_state)`` method will be called to handle any error that happened. +If ``hardware_interface::return_type::ERROR`` is returned from ``read()`` or ``write()`` methods of a hardware_interface class, ``on_error(previous_state)`` method will be called to handle any error that happened. Error handling follows the `node lifecycle `_. If successful ``CallbackReturn::SUCCESS`` is returned and hardware is again in ``UNCONFIGURED`` state, if any ``ERROR`` or ``FAILURE`` happens the hardware ends in ``FINALIZED`` state and can not be recovered. The only option is to reload the complete plugin, but there is currently no service for this in the Controller Manager. -Migration from Foxy to Galactic -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Migration from Foxy to newer versions +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Between Foxy and Galactic we made substantial changes to the interface of hardware components to enable management of their lifecycle. The following list shows a set of quick changes to port existing hardware components to Galactic: @@ -36,20 +37,29 @@ The following list shows a set of quick changes to port existing hardware compon 2. If using BaseInterface as base class then you should remove it. Specifically, change: -hardware_interface::BaseInterface to hardware_interface::[Actuator|Sensor|System]Interface + .. code-block:: c++ + + hardware_interface::BaseInterface + + to + + .. code-block:: c++ + + hardware_interface::[Actuator|Sensor|System]Interface 3. Remove include of headers ``base_interface.hpp`` and ``hardware_interface_status_values.hpp`` 4. Add include of header ``rclcpp_lifecycle/state.hpp`` although this may not be strictly necessary -5. replace first three lines in ``on_init`` to: +5. replace first three lines in ``on_init`` to + + .. code-block:: c++ -.. code-block:: c++ + if (hardware_interface::[Actuator|Sensor|System]Interface::on_init(info) != CallbackReturn::SUCCESS) + { + return CallbackReturn::ERROR; + } - if (hardware_interface::[Actuator|Sensor|System]Interface::on_init(info) != CallbackReturn::SUCCESS) - { - return CallbackReturn::ERROR; - } 6. Change last return of ``on_init`` to ``return CallbackReturn::SUCCESS;`` diff --git a/hardware_interface/doc/hardware_interface_types_userdoc.rst b/hardware_interface/doc/hardware_interface_types_userdoc.rst new file mode 100644 index 0000000000..b872416a32 --- /dev/null +++ b/hardware_interface/doc/hardware_interface_types_userdoc.rst @@ -0,0 +1,6 @@ +:github_url: https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/doc/hardware_interface_types_userdoc.rst + +.. _hardware_interface_types_userdoc: + +``ros2_control`` hardware interface types +========================================== diff --git a/hardware_interface/doc/writing_new_hardware_interface.rst b/hardware_interface/doc/writing_new_hardware_component.rst similarity index 98% rename from hardware_interface/doc/writing_new_hardware_interface.rst rename to hardware_interface/doc/writing_new_hardware_component.rst index 1ff4dc4420..698f6cf6e2 100644 --- a/hardware_interface/doc/writing_new_hardware_interface.rst +++ b/hardware_interface/doc/writing_new_hardware_component.rst @@ -1,9 +1,9 @@ -:github_url: https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/doc/writing_new_hardware_interface.rst +:github_url: https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/doc/writing_new_hardware_component.rst -.. _writing_new_hardware_interface: +.. _writing_new_hardware_component: -Writing a new hardware interface -================================= +Writing a Hardware Component +============================ In ros2_control hardware system components are libraries, dynamically loaded by the controller manager using the `pluginlib `_ interface. The following is a step-by-step guide to create source files, basic tests, and compile rules for a new hardware interface. From 84a2034f98be286a44fb7d7d14e9ec6d3e37946f Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Wed, 6 Sep 2023 14:03:37 +0000 Subject: [PATCH 2/3] Copy info from roadmap --- .../doc/hardware_interface_types_userdoc.rst | 134 +++++++++++++++++- 1 file changed, 133 insertions(+), 1 deletion(-) diff --git a/hardware_interface/doc/hardware_interface_types_userdoc.rst b/hardware_interface/doc/hardware_interface_types_userdoc.rst index b872416a32..41c72ac6a7 100644 --- a/hardware_interface/doc/hardware_interface_types_userdoc.rst +++ b/hardware_interface/doc/hardware_interface_types_userdoc.rst @@ -3,4 +3,136 @@ .. _hardware_interface_types_userdoc: ``ros2_control`` hardware interface types -========================================== +--------------------------------------------------------- + +The ``ros2_control`` framework provides a set of hardware interface types that can be used to implement a hardware component for a specific robot or device. The following sections describe the different hardware interface types and their usage. + +Joints +***************************** +````-tag groups the interfaces associated with the joints of physical robots and actuators. +They have command and state interfaces to set the goal values for hardware and read its current state. + +Sensors +***************************** +````-tag groups multiple state interfaces describing, e.g., internal states of hardware. + +GPIOs +***************************** +The ````-tag is used for describing input and output ports of a robotic device that cannot be associated with any joint or sensor. +Parsing of ````-tag is similar to this of a ````-tag having command and state interfaces. +The tag must have at least one ````- or ````-tag as a child. + +The keyword "gpio" is chosen for its generality. +Although strictly used for digital signals, it describes any electrical analog, digital signal, or physical value. + +The ```` tag can be used as a child of all three types of hardware interfaces, i.e., system, sensor, or actuator. + +Examples +***************************** +The following examples show how to use the different hardware interface types in a ``ros2_control`` URDF. +They can be combined together within the different hardware component types (system, actuator, sensor) (:ref:`see detailed documentation `) as follows + +1. Robot with multiple GPIO interfaces + + - RRBot System + - Digital: 4 inputs and 2 outputs + - Analog: 2 inputs and 1 output + - Vacuum valve at the flange (on/off) + + + .. code:: xml + + + + ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware + 2.0 + 3.0 + 2.0 + + + + -1 + 1 + + + + + + -1 + 1 + + + + + + + + + + + + + + + + + + + + + + + +2. Gripper with electrical and suction grasping possibilities + + - Multimodal gripper + - 1-DoF parallel gripper + - suction on/off + + .. code:: xml + + + + ros2_control_demo_hardware/MultimodalGripper + + + + 0 + 100 + + + + + + + + + +3. Force-Torque-Sensor with temperature feedback and adjustable calibration + + - 2D FTS + - Temperature feedback in °C + - Choice between 3 calibration matrices, i.e., calibration ranges + + .. code:: xml + + + + ros2_control_demo_hardware/ForceTorqueSensor2DHardware + 0.43 + + + + + kuka_tcp + 100 + 100 + + + + + + + + + From 147177254a2700dc76304d5fc093a5bffa53eea2 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Wed, 6 Sep 2023 16:27:48 +0000 Subject: [PATCH 3/3] Add info on broadcasters --- .../doc/hardware_interface_types_userdoc.rst | 16 ++++++++++++++-- 1 file changed, 14 insertions(+), 2 deletions(-) diff --git a/hardware_interface/doc/hardware_interface_types_userdoc.rst b/hardware_interface/doc/hardware_interface_types_userdoc.rst index 41c72ac6a7..54b2003568 100644 --- a/hardware_interface/doc/hardware_interface_types_userdoc.rst +++ b/hardware_interface/doc/hardware_interface_types_userdoc.rst @@ -5,17 +5,26 @@ ``ros2_control`` hardware interface types --------------------------------------------------------- -The ``ros2_control`` framework provides a set of hardware interface types that can be used to implement a hardware component for a specific robot or device. The following sections describe the different hardware interface types and their usage. +The ``ros2_control`` framework provides a set of hardware interface types that can be used to implement +a hardware component for a specific robot or device. +The following sections describe the different hardware interface types and their usage. Joints ***************************** ````-tag groups the interfaces associated with the joints of physical robots and actuators. They have command and state interfaces to set the goal values for hardware and read its current state. +State interfaces of joints can be published as a ROS topic by means of the :ref:`joint_state_broadcaster ` + Sensors ***************************** ````-tag groups multiple state interfaces describing, e.g., internal states of hardware. +Depending on the type of sensor, there exist a couple of specific semantic components with broadcasters shipped with ros2_controllers, e.g. + +- :ref:`Imu Sensor Broadcaster ` +- :ref:`Force Torque Sensor Broadcaster ` + GPIOs ***************************** The ````-tag is used for describing input and output ports of a robotic device that cannot be associated with any joint or sensor. @@ -25,7 +34,10 @@ The tag must have at least one ````- or ````-tag as a child. The keyword "gpio" is chosen for its generality. Although strictly used for digital signals, it describes any electrical analog, digital signal, or physical value. -The ```` tag can be used as a child of all three types of hardware interfaces, i.e., system, sensor, or actuator. +The ```` tag can be used as a child of all three types of hardware components, i.e., system, sensor, or actuator. + +Because ports implemented as ````-tag are typically very application-specific, there exists no generic publisher +within the ros2_control framework. A custom gpio-controller has to be implemented for each application. As an example, see :ref:`the GPIO controller example ` as part of the demo repository. Examples *****************************