Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Improve diagnostics strings #2078

Merged
merged 4 commits into from
Mar 1, 2025
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3356,8 +3356,8 @@ void ControllerManager::controller_activity_diagnostic_callback(
high_exec_time_controllers_string.append(" ");
}
stat.mergeSummary(
level,
"\nControllers with high execution time : [ " + high_exec_time_controllers_string + "]");
level, "\nControllers with high or varying execution time : [ " +
high_exec_time_controllers_string + "]");
}
if (!bad_periodicity_async_controllers.empty())
{
Expand All @@ -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, "\nControllers with bad or varying periodicity : [ " +
bad_periodicity_async_controllers_string + "]");
}

if (!atleast_one_hw_active)
Expand Down
24 changes: 12 additions & 12 deletions controller_manager/src/controller_manager_parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -33,15 +33,15 @@ 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,
}
}
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,
}
Expand All @@ -50,15 +50,15 @@ 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,
}
}
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,
}
Expand All @@ -69,15 +69,15 @@ 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,
}
}
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,
}
Expand All @@ -86,15 +86,15 @@ 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,
}
}
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,
}
Expand All @@ -104,15 +104,15 @@ 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,
}
}
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,
}
Expand All @@ -121,15 +121,15 @@ 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,
}
}
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,
}
Expand Down
Loading