AP_NavEKF: extend fusion fault reporting coverage

This commit is contained in:
Paul Riseborough 2016-05-10 16:01:26 +10:00 committed by Andrew Tridgell
parent 71b589c89c
commit d59d8cc6e3
4 changed files with 10 additions and 5 deletions

View File

@ -771,7 +771,7 @@ void NavEKF::setTouchdownExpected(bool val)
7 = badly conditioned synthetic sideslip fusion
7 = filter is not initialised
*/
void NavEKF::getFilterFaults(uint8_t &faults) const
void NavEKF::getFilterFaults(uint16_t &faults) const
{
if (core) {
core->getFilterFaults(faults);

View File

@ -201,7 +201,7 @@ public:
6 = 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

View File

@ -83,7 +83,7 @@ NavEKF_core::NavEKF_core(NavEKF &_frontend, const AP_AHRS *ahrs, AP_Baro &baro,
// Check basic filter health metrics and return a consolidated health status
bool NavEKF_core::healthy(void) const
{
uint8_t faultInt;
uint16_t faultInt;
getFilterFaults(faultInt);
if (faultInt > 0) {
return false;
@ -3918,6 +3918,11 @@ void NavEKF_core::readIMUData()
// just read primary gyro
readDeltaAngle(ins.get_primary_gyro(), dAngIMU);
}
//debug testing
if (imuSampleTime_ms > 300E3) {
dAngIMU.x += 0.01745f * dtDelAng;
}
}
// check for new valid GPS data and update stored measurement if available
@ -4583,7 +4588,7 @@ return the filter fault status as a bitmasked integer
6 = badly conditioned synthetic sideslip fusion
7 = filter is not initialised
*/
void NavEKF_core::getFilterFaults(uint8_t &faults) const
void NavEKF_core::getFilterFaults(uint16_t &faults) const
{
faults = (state.quat.is_nan()<<0 |
state.velocity.is_nan()<<1 |

View File

@ -244,7 +244,7 @@ public:
6 = 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