mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
ArduCopter: bug fix for compass.accumulate check in main loop (millis vs micros issue)
This commit is contained in:
parent
8d75022d58
commit
ad14e727e2
@ -1018,7 +1018,7 @@ void loop()
|
||||
#ifdef DESKTOP_BUILD
|
||||
usleep(1000);
|
||||
#endif
|
||||
if (timer - fast_loopTimer < 9) {
|
||||
if (timer - fast_loopTimer < 9000) {
|
||||
// we have some spare cycles available
|
||||
// less than 10ms has passed. We have at least one millisecond
|
||||
// of free time. The most useful thing to do with that time is
|
||||
|
Loading…
Reference in New Issue
Block a user