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
5 changes: 5 additions & 0 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2322,6 +2322,10 @@ std::vector<std::string> ControllerManager::get_controller_names()

void ControllerManager::read(const rclcpp::Time & time, const rclcpp::Duration & period)
{
if (periodicity_stats_.GetCount() >= 100)
Copy link
Contributor Author

Choose a reason for hiding this comment

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

the window size could be made configurable

Copy link
Member

Choose a reason for hiding this comment

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

good point. Could you please add a param for that? I think 100 is a good default value for resetting

Copy link
Member

Choose a reason for hiding this comment

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

I think it is better to leave it to the user to define it. If not defined, let it accumulate from the beginning.

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

Expand Down Expand Up @@ -3347,6 +3351,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
Loading