Skip to content

Commit

Permalink
Add note on why the factor 0.99 is used
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Oct 16, 2024
1 parent a3f4ba6 commit 07e1684
Showing 1 changed file with 6 additions and 0 deletions.
6 changes: 6 additions & 0 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 ==
Expand Down

0 comments on commit 07e1684

Please sign in to comment.