mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: fixed EKF compass switching
when we had 3 compasses the lack of the 'break' meant when we switched compass in flight we would always switch back instantly to the one that we had just rejected.
This commit is contained in:
parent
4003ea841c
commit
ccc1f906f8
|
@ -247,6 +247,7 @@ void NavEKF2_core::readMagData()
|
||||||
magStateResetRequest = true;
|
magStateResetRequest = true;
|
||||||
// declare the field unlearned so that the reset request will be obeyed
|
// declare the field unlearned so that the reset request will be obeyed
|
||||||
magFieldLearned = false;
|
magFieldLearned = false;
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue