mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_NavEKF3: Reset covariance if bad mag fusion update
This commit is contained in:
parent
18b66f9eed
commit
f208986d43
@ -695,6 +695,8 @@ void NavEKF3_core::FuseMagnetometer()
|
|||||||
} else if (obsIndex == 2) {
|
} else if (obsIndex == 2) {
|
||||||
faultStatus.bad_zmag = true;
|
faultStatus.bad_zmag = true;
|
||||||
}
|
}
|
||||||
|
CovarianceInit();
|
||||||
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user