mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_NavEKF2: extend fusion fault reporting coverage
This commit is contained in:
parent
0982bd0b2b
commit
71b589c89c
@ -962,7 +962,7 @@ void NavEKF2::setTouchdownExpected(bool val)
|
||||
7 = badly conditioned synthetic sideslip fusion
|
||||
7 = filter is not initialised
|
||||
*/
|
||||
void NavEKF2::getFilterFaults(int8_t instance, uint8_t &faults)
|
||||
void NavEKF2::getFilterFaults(int8_t instance, uint16_t &faults)
|
||||
{
|
||||
if (instance < 0 || instance >= num_cores) instance = primary;
|
||||
if (core) {
|
||||
|
@ -214,7 +214,7 @@ public:
|
||||
7 = badly conditioned synthetic sideslip fusion
|
||||
7 = filter is not initialised
|
||||
*/
|
||||
void getFilterFaults(int8_t instance, uint8_t &faults);
|
||||
void getFilterFaults(int8_t instance, uint16_t &faults);
|
||||
|
||||
/*
|
||||
return filter timeout status as a bitmasked integer for the specified instance
|
||||
|
@ -17,7 +17,7 @@ extern const AP_HAL::HAL& hal;
|
||||
// Check basic filter health metrics and return a consolidated health status
|
||||
bool NavEKF2_core::healthy(void) const
|
||||
{
|
||||
uint8_t faultInt;
|
||||
uint16_t faultInt;
|
||||
getFilterFaults(faultInt);
|
||||
if (faultInt > 0) {
|
||||
return false;
|
||||
@ -409,7 +409,7 @@ return the filter fault status as a bitmasked integer
|
||||
7 = badly conditioned synthetic sideslip fusion
|
||||
7 = filter is not initialised
|
||||
*/
|
||||
void NavEKF2_core::getFilterFaults(uint8_t &faults) const
|
||||
void NavEKF2_core::getFilterFaults(uint16_t &faults) const
|
||||
{
|
||||
faults = (stateStruct.quat.is_nan()<<0 |
|
||||
stateStruct.velocity.is_nan()<<1 |
|
||||
|
@ -202,7 +202,7 @@ public:
|
||||
7 = badly conditioned synthetic sideslip fusion
|
||||
7 = filter is not initialised
|
||||
*/
|
||||
void getFilterFaults(uint8_t &faults) const;
|
||||
void getFilterFaults(uint16_t &faults) const;
|
||||
|
||||
/*
|
||||
return filter timeout status as a bitmasked integer
|
||||
@ -878,6 +878,12 @@ private:
|
||||
bool bad_zmag:1;
|
||||
bool bad_airspeed:1;
|
||||
bool bad_sideslip:1;
|
||||
bool bad_nvel:1;
|
||||
bool bad_evel:1;
|
||||
bool bad_dvel:1;
|
||||
bool bad_npos:1;
|
||||
bool bad_epos:1;
|
||||
bool bad_dpos:1;
|
||||
} faultStatus;
|
||||
|
||||
// flags indicating which GPS quality checks are failing
|
||||
|
Loading…
Reference in New Issue
Block a user