mirror of https://github.com/ArduPilot/ardupilot
APM: accumulate mag readings during spare cycles in ArduPlane
With this change we average over 100 mag readings per compass.read() call, which means we are reading the compass at over 1kHz instead of 10Hz. The noise reduction is huge.
This commit is contained in:
parent
b555d86ec0
commit
a71cee4579
|
@ -747,6 +747,15 @@ void loop()
|
|||
}
|
||||
|
||||
fast_loopTimeStamp_ms = millis();
|
||||
} else {
|
||||
// less than 20ms has passed. We have at least one millisecond
|
||||
// of free time. The most useful thing to do with that time is
|
||||
// to accumulate some sensor readings, specifically the
|
||||
// compass, which is often very noisy but is not interrupt
|
||||
// driven, so it can't accumulate readings by itself
|
||||
if (g.compass_enabled) {
|
||||
compass.accumulate();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue