AP_NavEKF: add another health check in the EKF
if SV, SP and SH are all off then the most likely cause is divergence of the EKF. This was done based on a flight log with bad gyro cal
This commit is contained in:
parent
f84f432ecf
commit
8acfbb2ee0
@ -378,6 +378,12 @@ bool NavEKF::healthy(void) const
|
||||
if (state.velocity.is_nan()) {
|
||||
return false;
|
||||
}
|
||||
if (_fallback && velTestRatio > 1 && posTestRatio > 1 && hgtTestRatio > 1) {
|
||||
// all three metrics being above 1 means the filter is
|
||||
// extremely unhealthy.
|
||||
return false;
|
||||
}
|
||||
|
||||
// If measurements have failed innovation consistency checks for long enough to time-out
|
||||
// and force fusion then the nav solution can be conidered to be unhealthy
|
||||
// This will only be set as a transient
|
||||
|
Loading…
Reference in New Issue
Block a user