AP_AHRS: Add accessor function for airspeed health monitoring

This commit is contained in:
Paul Riseborough 2022-06-26 09:17:46 +10:00 committed by Randy Mackay
parent 66e26bb5cc
commit f613c4088e
2 changed files with 34 additions and 0 deletions

View File

@ -971,6 +971,36 @@ bool AP_AHRS::airspeed_vector_true(Vector3f &vec) const
return false;
}
// return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed
// returns false if the data is unavailable
bool AP_AHRS::airspeed_health_data(float &innovation, float &innovationVariance, uint32_t &age_ms) const
{
switch (active_EKF_type()) {
case EKFType::NONE:
break;
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
break;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.getAirSpdHealthData(innovation, innovationVariance, age_ms);
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
break;
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
case EKFType::EXTERNAL:
break;
#endif
}
return false;
}
// return a synthetic airspeed estimate (one derived from sensors
// other than an actual airspeed sensor), if available. return
// true if we have a synthetic airspeed. ret will not be modified

View File

@ -155,6 +155,10 @@ public:
// returns false if estimate is unavailable
bool airspeed_vector_true(Vector3f &vec) const;
// return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed
// returns false if the data is unavailable
bool airspeed_health_data(float &innovation, float &innovationVariance, uint32_t &age_ms) const;
// return true if airspeed comes from an airspeed sensor, as
// opposed to an IMU estimate
bool airspeed_sensor_enabled(void) const;