AP_NavEKF3: fixed switch to non-zero primary on disarm

if EK3_PRIMARY is not zero then we were not switching to it when
disarmed
This commit is contained in:
Andrew Tridgell 2021-11-03 06:29:31 +11:00
parent 2dd392ec4b
commit 86c481b4b0
1 changed files with 1 additions and 1 deletions

View File

@ -968,7 +968,7 @@ void NavEKF3::UpdateFilter(void)
}
const uint8_t user_primary = uint8_t(_primary_core) < num_cores? _primary_core : 0;
if (primary != 0 && core[user_primary].healthy() && !armed) {
if (primary != user_primary && core[user_primary].healthy() && !armed) {
// when on the ground and disarmed force the selected primary
// core. This avoids us ending with with a lottery for which
// IMU is used in each flight. Otherwise the alignment of the