Skip to content

Commit 9528bd7

Browse files
committed
Add parameters_context.yaml and move parameters documentation
1 parent 551abb5 commit 9528bd7

File tree

2 files changed

+27
-75
lines changed

2 files changed

+27
-75
lines changed
Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,21 @@
1+
hardware_components_initial_state: |
2+
Map of parameters for controlled lifecycle management of hardware components.
3+
The names of the components are defined as attribute of ``<ros2_control>``-tag in ``robot_description``.
4+
Hardware components found in ``robot_description``, but without explicit state definition will be immediately activated.
5+
Detailed explanation of each parameter is given below.
6+
The full structure of the map is given in the following example:
7+
8+
.. code-block:: yaml
9+
10+
hardware_components_initial_state:
11+
unconfigured:
12+
- "arm1"
13+
- "arm2"
14+
inactive:
15+
- "base3"
16+
17+
diagnostics.threshold.controllers.periodicity: |
18+
The ``periodicity`` diagnostics will be published only for the asynchronous controllers, because any affect to the synchronous controllers will be reflected directly in the controller manager's periodicity.
19+
20+
diagnostics.threshold.controllers.execution_time: |
21+
The ``execution_time`` diagnostics will be published for all controllers. The ``mean_error`` for a synchronous controller will be computed against zero, as it should be as low as possible. However, the ``mean_error`` for an asynchronous controller will be computed against the controller's desired update period, as the controller can take a maximum of the desired period cycle to execute it's update cycle.

controller_manager/doc/userdoc.rst

Lines changed: 6 additions & 75 deletions
Original file line numberDiff line numberDiff line change
@@ -57,32 +57,6 @@ robot_description [std_msgs::msg::String]
5757
Parameters
5858
-----------
5959

60-
hardware_components_initial_state
61-
Map of parameters for controlled lifecycle management of hardware components.
62-
The names of the components are defined as attribute of ``<ros2_control>``-tag in ``robot_description``.
63-
Hardware components found in ``robot_description``, but without explicit state definition will be immediately activated.
64-
Detailed explanation of each parameter is given below.
65-
The full structure of the map is given in the following example:
66-
67-
.. code-block:: yaml
68-
69-
hardware_components_initial_state:
70-
unconfigured:
71-
- "arm1"
72-
- "arm2"
73-
inactive:
74-
- "base3"
75-
76-
hardware_components_initial_state.unconfigured (optional; list<string>; default: empty)
77-
Defines which hardware components will be only loaded immediately when controller manager is started.
78-
79-
hardware_components_initial_state.inactive (optional; list<string>; default: empty)
80-
Defines which hardware components will be configured immediately when controller manager is started.
81-
82-
update_rate (mandatory; integer)
83-
The frequency of controller manager's real-time update loop.
84-
This loop reads states from hardware, updates controller and writes commands to hardware.
85-
8660
<controller_name>.type
8761
Name of a plugin exported using ``pluginlib`` for a controller.
8862
This is a class from which controller's instance with name "``controller_name``" is created.
@@ -99,58 +73,15 @@ update_rate (mandatory; integer)
9973
The fallback controllers activation is subject to the availability of the state and command interfaces at the time of activation.
10074
It is recommended to test the fallback strategy in simulation before deploying it on the real robot.
10175

102-
diagnostics.threshold.controller_manager.periodicity.mean_error.warn
103-
The warning threshold for the mean error of the controller manager's periodicity.
104-
If the mean error exceeds this threshold, a warning diagnostic will be published.
105-
106-
diagnostics.threshold.controller_manager.periodicity.mean_error.error
107-
The error threshold for the mean error of the controller manager's periodicity.
108-
If the mean error exceeds this threshold, an error diagnostic will be published.
109-
110-
diagnostics.threshold.controller_manager.periodicity.standard_deviation.warn
111-
The warning threshold for the standard deviation of the controller manager's periodicity.
112-
If the standard deviation exceeds this threshold, a warning diagnostic will be published.
113-
114-
diagnostics.threshold.controller_manager.periodicity.standard_deviation.error
115-
The error threshold for the standard deviation of the controller manager's periodicity.
116-
If the standard deviation exceeds this threshold, an error diagnostic will be published.
117-
118-
diagnostics.threshold.controllers.periodicity.mean_error.warn
119-
The warning threshold for the mean error of the controller update loop.
120-
If the mean error exceeds this threshold, a warning diagnostic will be published.
121-
122-
diagnostics.threshold.controllers.periodicity.mean_error.error
123-
The error threshold for the mean error of the controller update loop.
124-
If the mean error exceeds this threshold, an error diagnostic will be published.
125-
126-
diagnostics.threshold.controllers.periodicity.standard_deviation.warn
127-
The warning threshold for the standard deviation of the controller update loop.
128-
If the standard deviation exceeds this threshold, a warning diagnostic will be published.
129-
130-
diagnostics.threshold.controllers.periodicity.standard_deviation.error
131-
The error threshold for the standard deviation of the controller update loop.
132-
If the standard deviation exceeds this threshold, an error diagnostic will be published.
133-
134-
diagnostics.threshold.controllers.execution_time.mean_error.warn
135-
The warning threshold for the mean error of the controller execution time.
136-
If the mean error exceeds this threshold, a warning diagnostic will be published.
137-
138-
diagnostics.threshold.controllers.execution_time.mean_error.error
139-
The error threshold for the mean error of the controller execution time.
140-
If the mean error exceeds this threshold, an error diagnostic will be published.
141-
142-
diagnostics.threshold.controllers.execution_time.standard_deviation.warn
143-
The warning threshold for the standard deviation of the controller execution time.
144-
If the standard deviation exceeds this threshold, a warning diagnostic will be published.
76+
.. generate_parameter_library_details::
77+
../src/controller_manager_parameters.yaml
78+
parameters_context.yaml
14579

146-
diagnostics.threshold.controllers.execution_time.standard_deviation.error
147-
The error threshold for the standard deviation of the controller execution time.
148-
If the standard deviation exceeds this threshold, an error diagnostic will be published.
80+
**An example parameter file:**
14981

150-
.. note::
151-
The ``periodicity`` diagnostics will be published only for the asynchronous controllers, because any affect to the synchronous controllers will be reflected directly in the controller manager's periodicity.
82+
.. generate_parameter_library_default::
83+
../src/controller_manager_parameters.yaml
15284

153-
The ``execution_time`` diagnostics will be published for all controllers. The ``mean_error`` for a synchronous controller will be computed against zero, as it should be as low as possible. However, the ``mean_error`` for an asynchronous controller will be computed against the controller's desired update period, as the controller can take a maximum of the desired period cycle to execute it's update cycle.
15485

15586
Handling Multiple Controller Managers
15687
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0 commit comments

Comments
 (0)