ArduCopter: bug fix for compass.accumulate check in main loop (millis vs micros issue)
This commit is contained in:
parent
50d46898fb
commit
5633164fa0
@ -992,7 +992,7 @@ void loop()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
if (timer - fast_loopTimer < 9) {
|
if (timer - fast_loopTimer < 9000) {
|
||||||
// we have some spare cycles available
|
// we have some spare cycles available
|
||||||
// less than 10ms has passed. We have at least one millisecond
|
// less than 10ms has passed. We have at least one millisecond
|
||||||
// of free time. The most useful thing to do with that time is
|
// of free time. The most useful thing to do with that time is
|
||||||
|
Loading…
Reference in New Issue
Block a user