mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Plane: improved latency of main loop
use a 500usec delay
This commit is contained in:
parent
e6af7dad3d
commit
48ed480d59
@ -783,10 +783,8 @@ void loop()
|
||||
// the first call to the scheduler they won't run on a later
|
||||
// call until scheduler.tick() is called again
|
||||
scheduler.run(19000U);
|
||||
}
|
||||
if ((timer - fast_loopTimer_ms) <= 19) {
|
||||
// we have plenty of time - be friendly to multi-tasking OSes
|
||||
hal.scheduler->delay(1);
|
||||
} else {
|
||||
hal.scheduler->delay_microseconds(500);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user