mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
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:
parent
624de6443e
commit
ebc9616e00
@ -275,10 +275,19 @@ void AP_Scheduler::run(uint32_t time_available)
|
|||||||
perf_info.update_task_info(i, time_taken, overrun);
|
perf_info.update_task_info(i, time_taken, overrun);
|
||||||
|
|
||||||
if (time_taken >= time_available) {
|
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;
|
time_available = 0;
|
||||||
break;
|
} else {
|
||||||
|
time_available -= time_taken;
|
||||||
}
|
}
|
||||||
time_available -= time_taken;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// update number of spare microseconds
|
// update number of spare microseconds
|
||||||
|
Loading…
Reference in New Issue
Block a user