Skip to content

Commit

Permalink
Copy info from roadmap
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Sep 6, 2023
1 parent 1a81d0d commit 84a2034
Showing 1 changed file with 133 additions and 1 deletion.
134 changes: 133 additions & 1 deletion hardware_interface/doc/hardware_interface_types_userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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
*****************************
``<joint>``-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
*****************************
``<sensor>``-tag groups multiple state interfaces describing, e.g., internal states of hardware.

GPIOs
*****************************
The ``<gpio>``-tag is used for describing input and output ports of a robotic device that cannot be associated with any joint or sensor.
Parsing of ``<gpio>``-tag is similar to this of a ``<joint>``-tag having command and state interfaces.
The tag must have at least one ``<command>``- or ``<state>``-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 ``<gpio>`` 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 <overview_hardware_components>`) 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 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>
<gpio name="flange_analog_IOs">
<command_interface name="analog_output1"/>
<state_interface name="analog_output1"/> <!-- Needed to know current state of the output -->
<state_interface name="analog_input1"/>
<state_interface name="analog_input2"/>
</gpio>
<gpio name="flange_vacuum">
<command_interface name="vacuum"/>
<state_interface name="vacuum"/> <!-- Needed to know current state of the output -->
</gpio>
</ros2_control>
2. Gripper with electrical and suction grasping possibilities

- Multimodal gripper
- 1-DoF parallel gripper
- suction on/off

.. code:: xml
<ros2_control name="MultimodalGripper" type="actuator">
<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>
<gpio name="suction">
<command_interface name="suction"/>
<state_interface name="suction"/> <!-- Needed to know current state of the output -->
</gpio>
</ros2_control>
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 name="RRBotForceTorqueSensor2D" type="sensor">
<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>

0 comments on commit 84a2034

Please sign in to comment.