Skip to content

Commit

Permalink
Copter: don't sleep in rate loop in SITL
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Feb 11, 2024
1 parent 3e20746 commit 5bc2b1b
Showing 1 changed file with 3 additions and 0 deletions.
3 changes: 3 additions & 0 deletions ArduCopter/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,11 @@ void Copter::rate_controller_thread()
// run the rate controller
attitude_control->rate_controller_run_dt(dt);

#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
// ensure we give at least some CPU to other threads
// don't sleep on SITL where small sleeps are not possible
hal.scheduler->delay_microseconds(200);
#endif

if (is_zero(dt_avg)) {
dt_avg = dt;
Expand Down

0 comments on commit 5bc2b1b

Please sign in to comment.