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

Reset moving average #1984

Open
wants to merge 15 commits into
base: master
Choose a base branch
from
19 changes: 19 additions & 0 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2322,6 +2322,12 @@ std::vector<std::string> ControllerManager::get_controller_names()

void ControllerManager::read(const rclcpp::Time & time, const rclcpp::Duration & period)
{
if (
periodicity_stats_.GetCount() >=
params_->diagnostics.threshold.controller_manager.periodicity.window_size)
{
periodicity_stats_.Reset();
}
Comment on lines +2325 to +2330
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same here, this logic doesn't work for the default option
See the below comments for suggestions

periodicity_stats_.AddMeasurement(1.0 / period.seconds());
auto [ok, failed_hardware_names] = resource_manager_->read(time, period);

Expand Down Expand Up @@ -2499,11 +2505,23 @@ controller_interface::return_type ControllerManager::update(
controller_ret = trigger_result.result;
if (trigger_status && trigger_result.execution_time.has_value())
{
if (
loaded_controller.execution_time_statistics->GetCount() >=
params_->diagnostics.threshold.controllers.periodicity.window_size)
{
loaded_controller.execution_time_statistics->Reset();
}
Comment on lines +2508 to +2513
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same here, this logic doesn't work for the default option. Check the comments below

loaded_controller.execution_time_statistics->AddMeasurement(
static_cast<double>(trigger_result.execution_time.value().count()) / 1.e3);
}
if (!first_update_cycle && trigger_status && trigger_result.period.has_value())
{
if (
loaded_controller.periodicity_statistics->GetCount() >=
params_->diagnostics.threshold.controllers.periodicity.window_size)
{
loaded_controller.periodicity_statistics->Reset();
}
Comment on lines +2519 to +2524
Copy link
Member

@saikishor saikishor Jan 9, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Right now this logic will not work for default value -1 as the count will always be greater than window_size. Please check my recommendation to use the convention of seconds

Suggested change
if (
loaded_controller.periodicity_statistics->GetCount() >=
params_->diagnostics.threshold.controllers.periodicity.window_size)
{
loaded_controller.periodicity_statistics->Reset();
}
if ((std::finite(params_->diagnostics.threshold.controllers.window_size) &&
loaded_controller.periodicity_statistics->GetCount() >=
static_cast<unsigned int>(params_->diagnostics.threshold.controllers.window_size * update_rate_)))
{
loaded_controller.periodicity_statistics->Reset();
}

loaded_controller.periodicity_statistics->AddMeasurement(
1.0 / trigger_result.period.value().seconds());
}
Expand Down Expand Up @@ -3347,6 +3365,7 @@ void ControllerManager::controller_manager_diagnostic_callback(
const std::string periodicity_stat_name = "periodicity";
const auto cm_stats = periodicity_stats_.GetStatistics();
stat.add("update_rate", std::to_string(get_update_rate()));
stat.add(periodicity_stat_name + ".sample_count", std::to_string(cm_stats.sample_count));
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't know if this is an intuitive diagnostic for the user, moreover it tend to be a constant rather than a varying value

stat.add(periodicity_stat_name + ".average", std::to_string(cm_stats.average));
stat.add(
periodicity_stat_name + ".standard_deviation", std::to_string(cm_stats.standard_deviation));
Expand Down
10 changes: 10 additions & 0 deletions controller_manager/src/controller_manager_parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,11 @@ controller_manager:
threshold:
controller_manager:
periodicity:
window_size: {
type: int,
default_value: -1,
description: "The number of samples to consider for the mean. The diagnostics will be computed over the last `window_size` samples. -1 means that all samples will be considered.",
}
Comment on lines +32 to +36
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
window_size: {
type: int,
default_value: -1,
description: "The number of samples to consider for the mean. The diagnostics will be computed over the last `window_size` samples. -1 means that all samples will be considered.",
}
window_size: {
type: double,
default_value: .inf,
description: "The window size in seconds to consider for the mean. The diagnostics will be computed over the last `window_size` seconds. Default value infinity means that all data points will be considered.",
validation: {
gt<>: 0.0,
}
}

I believe the above validation works if you leave it with default value of infinity. I personally think it is more intuitive to the user to talk in seconds window rather than in the samples. What do you guys think?

mean_error:
warn: {
type: double,
Expand Down Expand Up @@ -65,6 +70,11 @@ controller_manager:
}
controllers:
periodicity:
window_size: {
type: int,
default_value: -1,
description: "The number of samples to consider for the mean. The diagnostics will be computed over the last `window_size` samples. -1 means that all samples will be considered.",
}
mean_error:
Comment on lines 71 to 78
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

controllers:
  window_size:
  periodicity:
    mean_error:

For the controllers, I believe this window_size should be a level higher, as it is being used for both periodicity and execution_time

warn: {
type: double,
Expand Down
Loading