Browse Source

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.
master
Andrew Tridgell 13 years ago
parent
commit
68705fe7e6
  1. 9
      ArduPlane/ArduPlane.pde

9
ArduPlane/ArduPlane.pde

@ -747,6 +747,15 @@ void loop() @@ -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…
Cancel
Save