mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: 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
ccc1f906f8
commit
39ffef1f08
|
@ -292,6 +292,7 @@ void NavEKF3_core::readMagData()
|
|||
magStateResetRequest = true;
|
||||
// declare the field unlearned so that the reset request will be obeyed
|
||||
magFieldLearned = false;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue