AP_NavEKF: Report unhealthy for all filter faults

This commit is contained in:
Paul Riseborough 2015-04-17 19:28:34 +10:00 committed by Randy Mackay
parent 6c4c54c2ba
commit 3e061b174e

View File

@ -434,13 +434,9 @@ NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro, const RangeFinder &rng) :
// Check basic filter health metrics and return a consolidated health status // Check basic filter health metrics and return a consolidated health status
bool NavEKF::healthy(void) const bool NavEKF::healthy(void) const
{ {
if (!statesInitialised) { uint8_t faultInt;
return false; getFilterFaults(faultInt);
} if (faultInt > 0) {
if (state.quat.is_nan()) {
return false;
}
if (state.velocity.is_nan()) {
return false; return false;
} }
if (_fallback && velTestRatio > 1 && posTestRatio > 1 && hgtTestRatio > 1) { if (_fallback && velTestRatio > 1 && posTestRatio > 1 && hgtTestRatio > 1) {