mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: save EKF learned compass to primary compass
This commit is contained in:
parent
2406e26ab4
commit
fea7632eac
@ -657,8 +657,8 @@ static void init_disarm_motors()
|
|||||||
|
|
||||||
// save compass offsets learned by the EKF
|
// save compass offsets learned by the EKF
|
||||||
Vector3f magOffsets;
|
Vector3f magOffsets;
|
||||||
if (ahrs.getMagOffsets(magOffsets)) {
|
if (ahrs.use_compass() && ahrs.getMagOffsets(magOffsets)) {
|
||||||
compass.set_and_save_offsets(0,magOffsets);
|
compass.set_and_save_offsets(compass.get_primary(), magOffsets);
|
||||||
}
|
}
|
||||||
|
|
||||||
#if AUTOTUNE_ENABLED == ENABLED
|
#if AUTOTUNE_ENABLED == ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user