mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
Copter: make the scheduling a bit more multi-tasking OS friendly
we can afford to sleep a bit in the main loop
This commit is contained in:
parent
0c99a1bbbb
commit
9e42e536a7
@ -988,6 +988,10 @@ void loop()
|
||||
uint32_t time_available = (timer + 10000) - micros();
|
||||
scheduler.run(time_available - 500);
|
||||
}
|
||||
if ((timer - fast_loopTimer) < 8500) {
|
||||
// we have plenty of time - be friendly to multi-tasking OSes
|
||||
hal.scheduler->delay(1);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user