You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
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.
18
+
The ``periodicity`` diagnostics will be published for the asynchronous controllers, because any affect to the synchronous controllers will be reflected directly in the controller manager's periodicity. It is also published for the synchronous controllers that have a different update rate than the controller manager update rate.
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.
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 to execute its update cycle.
The ``periodicity`` diagnostics will be published for the asynchronous hardware components, because any affect to the synchronous hardware components will be reflected directly in the controller manager's periodicity. It is also published for the synchronous hardware components that have a different read/write rate than the controller manager update rate.
The ``execution_time`` diagnostics will be published for all hardware components. The ``mean_error`` for a synchronous hardware component will be computed against zero, as it should be as low as possible. However, the ``mean_error`` for an asynchronous hardware component will be computed against its desired read/write period, as the hardware component can take a maximum of the desired period to execute the read/write cycle.
Copy file name to clipboardExpand all lines: controller_manager/src/controller_manager_parameters.yaml
+71
Original file line number
Diff line number
Diff line change
@@ -134,3 +134,74 @@ controller_manager:
134
134
gt<>: 0.0,
135
135
}
136
136
}
137
+
hardware_components:
138
+
periodicity:
139
+
mean_error:
140
+
warn: {
141
+
type: double,
142
+
default_value: 5.0,
143
+
description: "The warning threshold for the mean error of the hardware component's read/write loop in Hz. If the mean error exceeds this threshold, a warning diagnostic will be published.",
144
+
validation: {
145
+
gt<>: 0.0,
146
+
}
147
+
}
148
+
error: {
149
+
type: double,
150
+
default_value: 10.0,
151
+
description: "The error threshold for the mean error of the hardware component's read/write loop in Hz. If the mean error exceeds this threshold, an error diagnostic will be published.",
152
+
validation: {
153
+
gt<>: 0.0,
154
+
}
155
+
}
156
+
standard_deviation:
157
+
warn: {
158
+
type: double,
159
+
default_value: 5.0,
160
+
description: "The warning threshold for the standard deviation of the hardware component's read/write loop in Hz. If the standard deviation exceeds this threshold, a warning diagnostic will be published.",
161
+
validation: {
162
+
gt<>: 0.0,
163
+
}
164
+
}
165
+
error: {
166
+
type: double,
167
+
default_value: 10.0,
168
+
description: "The error threshold for the standard deviation of the hardware component's read/write loop in Hz. If the standard deviation exceeds this threshold, an error diagnostic will be published.",
169
+
validation: {
170
+
gt<>: 0.0,
171
+
}
172
+
}
173
+
execution_time:
174
+
mean_error:
175
+
warn: {
176
+
type: double,
177
+
default_value: 1000.0,
178
+
description: "The warning threshold for the mean error of the hardware component's read/write cycle execution time in microseconds. If the mean error exceeds this threshold, a warning diagnostic will be published.",
179
+
validation: {
180
+
gt<>: 0.0,
181
+
}
182
+
}
183
+
error: {
184
+
type: double,
185
+
default_value: 2000.0,
186
+
description: "The error threshold for the mean error of the hardware component's read/write cycle execution time in microseconds. If the mean error exceeds this threshold, a error diagnostic will be published.",
187
+
validation: {
188
+
gt<>: 0.0,
189
+
}
190
+
}
191
+
standard_deviation:
192
+
warn: {
193
+
type: double,
194
+
default_value: 100.0,
195
+
description: "The warning threshold for the standard deviation of the hardware component's read/write cycle execution time in microseconds. If the standard deviation exceeds this threshold, a warning diagnostic will be published.",
196
+
validation: {
197
+
gt<>: 0.0,
198
+
}
199
+
}
200
+
error: {
201
+
type: double,
202
+
default_value: 200.0,
203
+
description: "The error threshold for the standard deviation of the hardware component's update cycle execution time in microseconds. If the standard deviation exceeds this threshold, an error diagnostic will be published.",
Copy file name to clipboardExpand all lines: doc/release_notes.rst
+1
Original file line number
Diff line number
Diff line change
@@ -168,6 +168,7 @@ hardware_interface
168
168
* With (`#1567 <https://github.com/ros-controls/ros2_control/pull/1567>`_) all the Hardware components now have a fully functional asynchronous functionality, by simply adding ``is_async`` tag to the ros2_control tag in the URDF. This will allow the hardware components to run in a separate thread, and the controller manager will be able to run the controllers in parallel with the hardware components.
169
169
* The hardware components can be easily introspect the internal member variables using the macro ``REGISTER_ROS2_CONTROL_INTROSPECTION`` (`#1918 <https://github.com/ros-controls/ros2_control/pull/1918>`_)
170
170
* Added new ``get_optional`` method that returns ``std::optional`` of the templated type, and this can be used to check if the value is available or not (`#1976 <https://github.com/ros-controls/ros2_control/pull/1976>`_ and `#2061 <https://github.com/ros-controls/ros2_control/pull/2061>`_)
171
+
* Added hardware components execution time and periodicity statistics diagnostics (`#2086 <https://github.com/ros-controls/ros2_control/pull/2086>`_)
0 commit comments