diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 14fe41e1a2..f89fe11a4b 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -3357,7 +3357,7 @@ void ControllerManager::controller_activity_diagnostic_callback( } stat.mergeSummary( level, - "\nControllers with high execution time : [ " + high_exec_time_controllers_string + "]"); + "\nHigh execution jitter or mean error : [ " + high_exec_time_controllers_string + "]"); } if (!bad_periodicity_async_controllers.empty()) { @@ -3368,8 +3368,8 @@ void ControllerManager::controller_activity_diagnostic_callback( bad_periodicity_async_controllers_string.append(" "); } stat.mergeSummary( - level, - "\nControllers with bad periodicity : [ " + bad_periodicity_async_controllers_string + "]"); + level, "\nHigh periodicity jitter or mean error : [ " + + bad_periodicity_async_controllers_string + "]"); } if (!atleast_one_hw_active) diff --git a/controller_manager/src/controller_manager_parameters.yaml b/controller_manager/src/controller_manager_parameters.yaml index 1bb9b152b1..9041e883fb 100644 --- a/controller_manager/src/controller_manager_parameters.yaml +++ b/controller_manager/src/controller_manager_parameters.yaml @@ -33,7 +33,7 @@ controller_manager: warn: { type: double, default_value: 5.0, - description: "The warning threshold for the mean error of the controller manager's periodicity. If the mean error exceeds this threshold, a warning diagnostic will be published.", + description: "The warning threshold for the mean error of the controller manager's periodicity in Hz. If the mean error exceeds this threshold, a warning diagnostic will be published.", validation: { gt<>: 0.0, } @@ -41,7 +41,7 @@ controller_manager: error: { type: double, default_value: 10.0, - description: "The error threshold for the mean error of the controller manager's periodicity. If the mean error exceeds this threshold, an error diagnostic will be published.", + description: "The error threshold for the mean error of the controller manager's periodicity in Hz. If the mean error exceeds this threshold, an error diagnostic will be published.", validation: { gt<>: 0.0, } @@ -50,7 +50,7 @@ controller_manager: warn: { type: double, default_value: 5.0, - description: "The warning threshold for the standard deviation of the controller manager's periodicity. If the standard deviation exceeds this threshold, a warning diagnostic will be published.", + description: "The warning threshold for the standard deviation of the controller manager's periodicity in Hz. If the standard deviation exceeds this threshold, a warning diagnostic will be published.", validation: { gt<>: 0.0, } @@ -58,7 +58,7 @@ controller_manager: error: { type: double, default_value: 10.0, - description: "The error threshold for the standard deviation of the controller manager's periodicity. If the standard deviation exceeds this threshold, an error diagnostic will be published.", + description: "The error threshold for the standard deviation of the controller manager's periodicity in Hz. If the standard deviation exceeds this threshold, an error diagnostic will be published.", validation: { gt<>: 0.0, } @@ -69,7 +69,7 @@ controller_manager: warn: { type: double, default_value: 5.0, - description: "The warning threshold for the mean error of the controller update loop. If the mean error exceeds this threshold, a warning diagnostic will be published. This 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.", + description: "The warning threshold for the mean error of the controller update loop in Hz. If the mean error exceeds this threshold, a warning diagnostic will be published.", validation: { gt<>: 0.0, } @@ -77,7 +77,7 @@ controller_manager: error: { type: double, default_value: 10.0, - description: "The error threshold for the mean error of the controller update loop. If the mean error exceeds this threshold, an error diagnostic will be published. This 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.", + description: "The error threshold for the mean error of the controller update loop in Hz. If the mean error exceeds this threshold, an error diagnostic will be published.", validation: { gt<>: 0.0, } @@ -86,7 +86,7 @@ controller_manager: warn: { type: double, default_value: 5.0, - description: "The warning threshold for the standard deviation of the controller update loop. If the standard deviation exceeds this threshold, a warning diagnostic will be published. This 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.", + description: "The warning threshold for the standard deviation of the controller update loop in Hz. If the standard deviation exceeds this threshold, a warning diagnostic will be published.", validation: { gt<>: 0.0, } @@ -94,7 +94,7 @@ controller_manager: error: { type: double, default_value: 10.0, - description: "The error threshold for the standard deviation of the controller update loop. If the standard deviation exceeds this threshold, an error diagnostic will be published. This 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.", + description: "The error threshold for the standard deviation of the controller update loop in Hz. If the standard deviation exceeds this threshold, an error diagnostic will be published.", validation: { gt<>: 0.0, } @@ -104,7 +104,7 @@ controller_manager: warn: { type: double, default_value: 1000.0, - description: "The warning threshold for the mean error of the controller's update cycle execution time in microseconds. If the mean error exceeds this threshold, a warning diagnostic will be published. 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", + description: "The warning threshold for the mean error of the controller's update cycle execution time in microseconds. If the mean error exceeds this threshold, a warning diagnostic will be published.", validation: { gt<>: 0.0, } @@ -112,7 +112,7 @@ controller_manager: error: { type: double, default_value: 2000.0, - description: "The error threshold for the mean error of the controller's update cycle execution time in microseconds. If the mean error exceeds this threshold, an error diagnostic will be published. 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", + description: "The error threshold for the mean error of the controller's update cycle execution time in microseconds. If the mean error exceeds this threshold, an error diagnostic will be published.", validation: { gt<>: 0.0, } @@ -121,7 +121,7 @@ controller_manager: warn: { type: double, default_value: 100.0, - description: "The warning threshold for the standard deviation of the controller's update cycle execution time. If the standard deviation exceeds this threshold, a warning diagnostic will be published.", + description: "The warning threshold for the standard deviation of the controller's update cycle execution time in microseconds. If the standard deviation exceeds this threshold, a warning diagnostic will be published.", validation: { gt<>: 0.0, } @@ -129,7 +129,7 @@ controller_manager: error: { type: double, default_value: 200.0, - description: "The error threshold for the standard deviation of the controller's update cycle execution time. If the standard deviation exceeds this threshold, an error diagnostic will be published.", + description: "The error threshold for the standard deviation of the controller's update cycle execution time in microseconds. If the standard deviation exceeds this threshold, an error diagnostic will be published.", validation: { gt<>: 0.0, }