diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index 23f7fd8081..7e3204e7ee 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -657,8 +657,8 @@ static void init_disarm_motors() // save compass offsets learned by the EKF Vector3f magOffsets; - if (ahrs.getMagOffsets(magOffsets)) { - compass.set_and_save_offsets(0,magOffsets); + if (ahrs.use_compass() && ahrs.getMagOffsets(magOffsets)) { + compass.set_and_save_offsets(compass.get_primary(), magOffsets); } #if AUTOTUNE_ENABLED == ENABLED