diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 34566f95b3..c90ca85973 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -2322,6 +2322,12 @@ std::vector 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(); + } periodicity_stats_.AddMeasurement(1.0 / period.seconds()); auto [ok, failed_hardware_names] = resource_manager_->read(time, period); @@ -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(); + } loaded_controller.execution_time_statistics->AddMeasurement( static_cast(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(); + } loaded_controller.periodicity_statistics->AddMeasurement( 1.0 / trigger_result.period.value().seconds()); } @@ -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)); 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)); diff --git a/controller_manager/src/controller_manager_parameters.yaml b/controller_manager/src/controller_manager_parameters.yaml index 1bb9b152b1..79d98bad36 100644 --- a/controller_manager/src/controller_manager_parameters.yaml +++ b/controller_manager/src/controller_manager_parameters.yaml @@ -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.", + } mean_error: warn: { type: double, @@ -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: warn: { type: double,