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:
Andrew Tridgell 2013-09-28 21:22:59 +10:00
parent 0c99a1bbbb
commit 9e42e536a7

View File

@ -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);
}
}