ArduCopter: bug fix for compass.accumulate check in main loop (millis vs micros issue)

This commit is contained in:
rmackay9 2012-12-12 23:29:57 +09:00
parent 8d75022d58
commit ad14e727e2

View File

@ -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