AP_Scheduler: guarantee that FAST_TASK tasks do run on every loop

the breakup of the fast loop resulted in us sometimes (under heavy CPU
load) not running a fast task on every loop
This commit is contained in:
Andrew Tridgell 2022-12-05 21:25:32 +11:00 committed by Randy Mackay
parent 105daa9734
commit 18bbf68332
1 changed files with 11 additions and 2 deletions

View File

@ -275,10 +275,19 @@ void AP_Scheduler::run(uint32_t time_available)
perf_info.update_task_info(i, time_taken, overrun);
if (time_taken >= time_available) {
/*
we are out of time, but we need to keep walking the task
table in case there is another fast loop task after this
task, plus we need to update the accouting so we can
work out if we need to allocate extra time for the loop
(lower the loop rate)
Just set time_available to zero, which means we will
only run fast tasks after this one
*/
time_available = 0;
break;
} else {
time_available -= time_taken;
}
time_available -= time_taken;
}
// update number of spare microseconds