mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
Copter: fix underflow in scheduler
If fast_loop method executed time is over MAIN_LOOP_MICROS, scheduler.run method set value is 0.
This commit is contained in:
parent
0ed5665193
commit
4eee3b1317
@ -238,7 +238,7 @@ void Copter::loop()
|
||||
// the first call to the scheduler they won't run on a later
|
||||
// call until scheduler.tick() is called again
|
||||
uint32_t time_available = (timer + MAIN_LOOP_MICROS) - micros();
|
||||
scheduler.run(time_available);
|
||||
scheduler.run(time_available > MAIN_LOOP_MICROS ? 0u : time_available);
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user