mirror of https://github.com/ArduPilot/ardupilot
Copter: loop through compasses and save offsets
This commit is contained in:
parent
6a5f1c0bec
commit
c9b1b02b8e
|
@ -222,9 +222,13 @@ void Copter::init_disarm_motors()
|
|||
#endif
|
||||
|
||||
// save compass offsets learned by the EKF
|
||||
Vector3f magOffsets;
|
||||
if (ahrs.use_compass() && ahrs.getMagOffsets(magOffsets)) {
|
||||
compass.set_and_save_offsets(compass.get_primary(), magOffsets);
|
||||
if (ahrs.use_compass()) {
|
||||
for(uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
|
||||
Vector3f magOffsets;
|
||||
if (ahrs.getMagOffsets(i, magOffsets)) {
|
||||
compass.set_and_save_offsets(i, magOffsets);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
|
|
Loading…
Reference in New Issue