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 committed by Andrew Tridgell
parent 50d46898fb
commit 5633164fa0
1 changed files with 1 additions and 1 deletions

View File

@ -992,7 +992,7 @@ void loop()
}
}
} else {
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