Browse Source

Copter : Save EKF learned compass offsets on disarm

Requires compass learning to be enabled in the compass parameters

Copter: fix compass offsets patch
master
Paul Riseborough 10 years ago committed by Randy Mackay
parent
commit
2406e26ab4
  1. 7
      ArduCopter/motors.pde

7
ArduCopter/motors.pde

@ -655,9 +655,10 @@ static void init_disarm_motors() @@ -655,9 +655,10 @@ static void init_disarm_motors()
motors.armed(false);
// save offsets if automatic offset learning is on
if (compass.learn_offsets_enabled()) {
compass.save_offsets();
// save compass offsets learned by the EKF
Vector3f magOffsets;
if (ahrs.getMagOffsets(magOffsets)) {
compass.set_and_save_offsets(0,magOffsets);
}
#if AUTOTUNE_ENABLED == ENABLED

Loading…
Cancel
Save