From 07e1684c012529278b008d1000b7393e2b4bf505 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Fri, 4 Oct 2024 11:04:07 +0200 Subject: [PATCH] Add note on why the factor 0.99 is used --- controller_manager/src/controller_manager.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index e4ee4011b7..44519374aa 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -2365,6 +2365,12 @@ controller_interface::return_type ControllerManager::update( const auto controller_actual_period = (current_time - *loaded_controller.last_update_cycle_time); + /// @note The factor 0.99 is used to avoid the controllers skipping update cycles due to the + /// jitter in the system sleep cycles. + // For instance, A controller running at 50 Hz and the CM running at 100Hz, then when we have + // an update cycle at 0.019s (ideally, the controller should only trigger >= 0.02s), if we + // wait for next cycle, then trigger will happen at ~0.029 sec and this is creating an issue + // to keep up with the controller update rate (see issue #1769). const bool controller_go = run_controller_at_cm_rate || (time ==