Skip to content

Commit 39d6ca9

Browse files
destoglbmagyar
andauthored
Documentation for ros2_control (#36)
* Documentation for ros2_control * Update ros2_control_documentation.rst * Update ros2_control_documentation.rst * Update ros2_control_documentation.rst * Update ros2_control_documentation.rst * Update ros2_control_documentation.rst * Update ros2_control_documentation.rst * Update ros2_control_documentation.rst * Apply suggestions from code review Co-authored-by: Bence Magyar <[email protected]> * Update ros2_control_documentation.rst * Update ros2_control_documentation.rst * Update ros2_control_documentation.rst Co-authored-by: Bence Magyar <[email protected]>
1 parent 2fb6373 commit 39d6ca9

File tree

1 file changed

+279
-0
lines changed

1 file changed

+279
-0
lines changed
Lines changed: 279 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,279 @@
1+
===========================
2+
ros2_control Framework
3+
===========================
4+
5+
The ros2_control is a framework for (real-time) control of robots using `ROS` (`Robot Operating System <http://ros.org>`__).
6+
Its packages are a rewrite of `ros_control <http://wiki.ros.org/ros_control>`__ packages to simplify integrating new hardware and overcome some drawbacks.
7+
8+
If you are not familiar with the control theory, please get some idea about it (e.g., at `Wikipedia <https://en.wikipedia.org/wiki/Control_theory>`_) to get familiar with the terms used in this manual.
9+
10+
.. contents:: Table of Contents
11+
:depth: 2
12+
13+
Overview
14+
========
15+
The ros2_control framework's source can be found in `ros-controlls/ros2_control`_ and `ros-controls/ros2_controllers`_ GitHub-repositories.
16+
The following figure shows the Architecture of the ros2_control framework.
17+
18+
|ros2_control_architecture|
19+
20+
Controller Manager
21+
------------------
22+
The `Controller Manager`_ (CM) connects the controllers' and hardware-abstraction sides of the ros2_control framework.
23+
It also serves as the entry-point for users through ROS services.
24+
The CM implements a node without an executor so it can be integrated into a custom setup.
25+
Still, for a standard user, it is recommended to use the default node-setup implemented in `ros2_control_node <https://github.com/ros-controls/ros2_control/blob/master/controller_manager/src/ros2_control_node.cpp>`_ file from the ``controller_manager`` package.
26+
This manual assumes that you use this default node-setup.
27+
28+
On the one side, CM manages (e.g., loading, activating, deactivating, unloading) controllers and from them required interfaces.
29+
On the other side, it has access to the hardware components (through Resource Manager), i.e., their interfaces.
30+
The Controller Manager matches *required* and *provided* interfaces, gives controllers access to hardware when activated, or reports an error if there is an access conflict.
31+
32+
The execution of the control-loop is managed by the CM's ``update()`` method.
33+
The method reads data from the hardware components, updates outputs of all active controllers, and writes the result to the components.
34+
35+
Resource Manager
36+
----------------
37+
The `Resource Manager`_ (RM) abstracts physical hardware and its drivers (called *hardware components*) for the ros2_control framework.
38+
The RM loads the components using ``pluginlib``-library, manages their lifecycle and components' state and command interfaces.
39+
This abstraction provided by RM enables re-usability of implemented hardware components, e.g., robot and gripper, without any implementation and flexible hardware application for state and command interfaces, e.g., separate hardware/communication libraries for motor control and encoder reading.
40+
41+
In the control loop execution, the RM's ``read()`` and ``write()`` methods deal with communication to the hardware components.
42+
43+
.. _overview-controllers:
44+
Controllers
45+
-----------
46+
The controllers in the ros2_control framework have the same functionality as defined in the control theory. They compare the reference value with the measured output and, based on this error, calculate a system's input (for more details, visit `Wikipedia <https://en.wikipedia.org/wiki/Control_theory>`_).
47+
The controlles are objects derived from `ControllerInterface`_ (``controller_interface`` package in `ros-controls/ros2_control`_) and exported as plugins using ``pluginlib``-library.
48+
For example of on controller check `ForwardCommandController implementation`_ in the `ros-controls/ros2_controllers`_ repository.
49+
The controllers' lifecycle is based on the `LifecycleNode-Class`_ implementing the state machine as described in the `Node Lifecycle Design`_ document.
50+
51+
When executing the control-loop ``update()`` method is called.
52+
The method can access the latest hardware states and enable the controller to write the hardware's command interfaces.
53+
54+
User Interfaces
55+
---------------
56+
Users interact with the ros2_control framework using `Controller Manager`_'s services.
57+
Those can be used directly or through the "cli"-interface (base command: ``ros2 control``).
58+
The "cli"-interface is more user-friendly for direct interaction, i.e., outside of a node.
59+
60+
For a list of services and their definitions, check the ``srv`` folder in the `controller_manager_msgs`_ package.
61+
62+
For the description of the "cli"-interface, see the ``README.md`` file of the `ros2controlcli`_ package.
63+
64+
65+
Hardware Components
66+
===================
67+
The *hardware components* realize communication to physical hardware and represent its abstraction in the ros2_control framework.
68+
The components have to be exported as plugins using ``pluginlib``-library.
69+
The `Resource Manager`_ dynamically loads those plugins and manages their lifecycle.
70+
71+
There are three basic types of components:
72+
73+
System
74+
Complex (multi-DOF) robotic hardware like industrial robots.
75+
The main difference between the *Actuator* component is the possibility to use complex transmissions like needed for humanoid robot's hands.
76+
This component has reading and writing capabilities.
77+
It is used when the is only one logical communication channel to the hardware (e.g., KUKA-RSI).
78+
79+
Sensor
80+
Robotic hardware is used for sensing its environment.
81+
A sensor component is related to a joint (e.g., encoder) or a link (e.g., force-torque sensor).
82+
This component type has only reading capabilities.
83+
84+
Actuator
85+
Simple (1 DOF) robotic hardware like motors, valves, and similar.
86+
An actuator implementation is related to only one joint.
87+
This component type has reading and writing capabilities. Reading is not mandatory if not possible (e.g., DC motor control with Arduino board).
88+
The actuator type can also be used with a multi-DOF robot if its hardware enables modular design, e.g., CAN-communication with each motor independently.
89+
90+
91+
A detailed explanation of hardware components is given in the `Hardware Access through Controllers design document`_.
92+
93+
Hardware Description in URDF
94+
----------------------------
95+
The ros2_control framework uses the ``<ros2_control>``-tag in the robot's URDF file to describe its components, i.e., the hardware setup.
96+
The chosen structure enables tracking together multiple `xacro`-macros into one without any changes.
97+
The example hereunder shows a position-controlled robot with 2-DOF (RRBot), an external 1-DOF force-torque sensor, and an externally controlled 1-DOF parallel gripper as its end-effector.
98+
For more examples and detailed explanations, check `ros-controls/ros2_control_demos`_ repository and `ROS2 Control Components URDF Examples design document`_.
99+
100+
.. code:: xml
101+
102+
<ros2_control name="RRBotSystemPositionOnly" type="system">
103+
<hardware>
104+
<plugin>ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware</plugin>
105+
<param name="example_param_write_for_sec">2</param>
106+
<param name="example_param_read_for_sec">2</param>
107+
</hardware>
108+
<joint name="joint1">
109+
<command_interface name="position">
110+
<param name="min">-1</param>
111+
<param name="max">1</param>
112+
</command_interface>
113+
<state_interface name="position"/>
114+
</joint>
115+
<joint name="joint2">
116+
<command_interface name="position">
117+
<param name="min">-1</param>
118+
<param name="max">1</param>
119+
</command_interface>
120+
<state_interface name="position"/>
121+
</joint>
122+
</ros2_control>
123+
<ros2_control name="RRBotForceTorqueSensor1D" type="sensor">
124+
<hardware>
125+
<plugin>ros2_control_demo_hardware/ForceTorqueSensor1DHardware</plugin>
126+
<param name="example_param_read_for_sec">0.43</param>
127+
</hardware>
128+
<sensor name="tcp_fts_sensor">
129+
<state_interface name="force"/>
130+
<param name="frame_id">rrbot_tcp</param>
131+
<param name="min_force">-100</param>
132+
<param name="max_force">100</param>
133+
</sensor>
134+
</ros2_control>
135+
<ros2_control name="RRBotGripper" type="actuator">
136+
<hardware>
137+
<plugin>ros2_control_demo_hardware/PositionActuatorHardware</plugin>
138+
<param name="example_param_write_for_sec">1.23</param>
139+
<param name="example_param_read_for_sec">3</param>
140+
</hardware>
141+
<joint name="gripper_joint ">
142+
<command_interface name="position">
143+
<param name="min">0</param>
144+
<param name="max">50</param>
145+
</command_interface>
146+
<state_interface name="position"/>
147+
<state_interface name="velocity"/>
148+
</joint>
149+
</ros2_control>
150+
151+
152+
Running the Framework for Your Robot
153+
------------------------------------
154+
To run the ros2_control framework, do the following.
155+
The example files can be found in the `ros2_control_demos`_ repository.
156+
157+
#. Create a YAML file with the configuration of the controller manager and controllers. (`Example for RRBot <https://github.com/ros-controls/ros2_control_demos/blob/master/ros2_control_demo_robot/controllers/rrbot_forward_controller_position.yaml>`_)
158+
#. Extend the robot's URDF description with needed ``<ros2_control>`` tags.
159+
It is recommended to use macro files instead of pure URDF. (`Example for RRBot <https://github.com/ros-controls/ros2_control_demos/blob/master/ros2_control_demo_robot/description/rrbot_system_position_only.urdf.xacro>`_)
160+
#. Create a launch file to start the node with `Controller Manager`_.
161+
You can use a default `ros2_control node`_ (recommended) or integrate the controller manager in your software stack.
162+
(`Example launch file for RRBot <https://github.com/ros-controls/ros2_control_demos/blob/master/ros2_control_demo_robot/launch/rrbot_system_position_only.launch.py>`_)
163+
164+
Repositories
165+
============
166+
The ros2_control framework consist of the following repositories:
167+
168+
ros2_control
169+
The `ros2_control`_ repository implements the main interfaces and components of the framework mentioned in the previous sections.
170+
171+
ros2_controllers
172+
The `ros2_controllers`_ repository implements widely used controllers, e.g., forward controller, joint trajectory controller, differential drive controller, etc.
173+
174+
ros2_control_demos
175+
The `ros2_control_demos`_ repository provides examples of using the framework and templates for a smooth start with it.
176+
177+
Differences to ros_control (ROS1)
178+
=================================
179+
180+
Hardware Structures - classes
181+
-----------------------------
182+
183+
The ros_control framework uses the ``RobotHW`` class as a rigid structure to handle any hardware.
184+
This makes it impossible to extend the existing robot with additional hardware, like sensors, actuators, and tools, without coding.
185+
The ``CombinedRobotHardware`` corrects this drawback.
186+
Still, this solution is not optimal, especially when combining robots with external sensors.
187+
188+
The ros2_control framework defines three types of hardware ``Actuator``, ``Sensor`` and ``System``.
189+
Using a combination (composition) of those basic components, any physical robotic cell (robot and its surrounding) can be described.
190+
This also means that multi-robot, robot-sensor, robot-gripper combinations are supported out of the box.
191+
Section `Hardware Components <#hardware-components>`__ describes this in detail.
192+
193+
Hardware Interfaces
194+
-------------------
195+
196+
The ros_control allows only three types of interfaces (joints), i.e., ``position``, ``velocity``, and ``effort``. The ``RobotHW`` class makes it very hard to use any other data to control the robot.
197+
198+
The ros2_control does not mandate a fixed set of interface types, but they are defined as strings in `hardware's description <#hardware-description-in-urdf>`__.
199+
To ensure compatibility of standard controllers, standard interfaces are defined as constants in `hardware_interface package <https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/include/hardware_interface/types/hardware_interface_type_values.hpp>`__.
200+
201+
Controller's Access to Hardware
202+
-------------------------------
203+
204+
In ros_control, the controllers had direct access to the ``RobotHW`` class requesting access to its interfaces (joints).
205+
The hardware itself then took care of registered interfaces and resource conflicts.
206+
207+
In ros2_control, ``ResourceManager`` takes care of the state of available interfaces in the framework and enables controllers to access the hardware.
208+
Also, the controllers do not have direct access to hardware anymore, but they register their interfaces to the `ControllerManager`.
209+
210+
Migration Guide to ros2_control
211+
===============================
212+
213+
RobotHardware to Components
214+
---------------------------
215+
#. The implementation of ``RobotHW`` is not used anymore.
216+
This should be migrated to SystemInterface`_ class or, for more granularity, `SensorInterface`_ and `ActuatorInterface`_.
217+
See the above description of "Hardware Components" to choose a suitable strategy.
218+
#. Decide which component type is suitable for your case. Maybe it makes sense to separate ``RobotHW`` into multiple components.
219+
#. Implement `ActuatorInterface`_, `SensorInterface`_ or `SystemInterface`_ classes as follows:
220+
221+
#. In the constructor, initialize all variables needed for communication with your hardware or define the default one.
222+
#. In the configure function, read all the parameters your hardware needs from the parsed URDF snippet (i.e., from the `HardwareInfo`_ structure). Here you can cross-check if all joints and interfaces in URDF have allowed values or a combination of values.
223+
#. Define interfaces to and from your hardware using ``export_*_interfaces`` functions.
224+
The names are ``<joint>/<interface>`` (e.g., ``joint_a2/position``).
225+
This can be extracted from the `HardwareInfo`_ structure or be hard-coded if sensible.
226+
#. Implement ``start`` and ``stop`` methods for your hardware.
227+
This usually includes changing the hardware state to receive commands or set it into a safe state before interrupting the command stream.
228+
It can also include starting and stopping communication.
229+
#. Implement `read` and `write` methods to exchange commands with the hardware.
230+
This method is equivalent to those from `ŔobotHW`-class in ROS1.
231+
#. Do not forget the ``PLUGINLIB_EXPORT_CLASS`` macro at the end of the .cpp file.
232+
#. Create .xml library description for the pluginlib, for example see `RRBotSystemPositionOnlyHardware <https://github.com/ros-controls/ros2_control_demos/blob/master/ros2_control_demo_hardware/ros2_control_demo_hardware.xml>`_.
233+
234+
235+
Controller Migration
236+
--------------------
237+
An excellent example of a migrated controller is the `JointTrajectoryController`_.
238+
The real-time critical methods are marked as such.
239+
240+
#. Implement `ControllerInterface`_ class as follows:
241+
242+
#. If there are any member variables, initialized those in the constructor.
243+
#. In the `init` method, first call ``ControllerInterface::init`` initialize lifecycle of the controller.
244+
Then declare all parameters defining their default values.
245+
#. Implement the ``state_interface_configuration()`` and ``command_interface_configuration()`` methods.
246+
#. Implement ``update()`` function for the controller. (**real-time**)
247+
#. Then implement required lifecycle methods (others are optional):
248+
* ``on_configure`` - reads parameters and configures controller.
249+
* ``on_activate`` - called when controller is activated (started) (**real-time**)
250+
* ``on_deactivate`` - called when controller is deactivated (stopped) (**real-time**)
251+
#. Do not forget ``PLUGINLIB_EXPORT_CLASS`` macro at the end of the .cpp file.
252+
#. Create .xml library description for the pluginlib, for example see `JointTrajectoryController <https://github.com/ros-controls/ros2_controllers/blob/master/joint_trajectory_controller/joint_trajectory_plugin.xml>`_.
253+
254+
255+
256+
.. _ros-controls/ros2_control: https://github.com/ros-controls/ros2_control
257+
.. _ros-controls/ros2_controllers: https://github.com/ros-controls/ros2_controllers
258+
.. _ros-controls/ros2_control_demos: https://github.com/ros-controls/ros2_control_demos
259+
.. _controller_manager_msgs: https://github.com/ros-controls/ros2_control/tree/master/controller_manager_msgs
260+
.. _Controller Manager: https://github.com/ros-controls/ros2_control/blob/master/controller_manager/src/controller_manager.cpp
261+
.. _ControllerInterface: https://github.com/ros-controls/ros2_control/blob/master/controller_interface/include/controller_interface/controller_interface.hpp
262+
.. _ros2_control node: https://github.com/ros-controls/ros2_control/blob/master/controller_manager/src/ros2_control_node.cpp
263+
.. _ForwardCommandController implementation: https://github.com/ros-controls/ros2_controllers/blob/master/forward_command_controller/src/forward_command_controller.cpp
264+
.. _Resource Manager: https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/src/resource_manager.cpp
265+
.. _LifecycleNode-Class: https://github.com/ros2/rclcpp/blob/master/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp
266+
.. _JointTrajectoryController: https://github.com/ros-controls/ros2_controllers/blob/master/joint_trajectory_controller/src/joint_trajectory_controller.cpp
267+
.. _Node Lifecycle Design: https://design.ros2.org/articles/node_lifecycle.html
268+
.. _ros2controlcli: https://github.com/ros-controls/ros2_control/tree/master/ros2controlcli
269+
.. _Hardware Access through Controllers design document: https://github.com/ros-controls/roadmap/blob/master/design_drafts/hardware_access.md
270+
.. _ROS2 Control Components URDF Examples design document: https://github.com/ros-controls/roadmap/blob/master/design_drafts/components_architecture_and_urdf_examples.md
271+
272+
.. _ActuatorInterface: https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/include/hardware_interface/actuator_interface.hpp
273+
.. _SensorInterface: https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/include/hardware_interface/sensor_interface.hpp
274+
.. _SystemInterface: https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/include/hardware_interface/system_interface.hpp
275+
.. _HardwareInfo: https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/include/hardware_interface/hardware_info.hpp
276+
277+
278+
.. |ros2_control_architecture| image:: images/components_architecture.png
279+
:alt: "ros2_control Architecture"

0 commit comments

Comments
 (0)