Copter: loop through compasses and save offsets

This commit is contained in:
Jonathan Challinger 2016-03-29 13:07:22 -07:00 committed by Andrew Tridgell
parent 6a5f1c0bec
commit c9b1b02b8e
1 changed files with 7 additions and 3 deletions

View File

@ -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