mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_NavEKF: Report unhealthy for all filter faults
This commit is contained in:
parent
6c4c54c2ba
commit
3e061b174e
@ -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) {
|
||||||
|
Loading…
Reference in New Issue
Block a user