mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_AHRS: Add accessor function for airspeed health monitoring
This commit is contained in:
parent
66e26bb5cc
commit
f613c4088e
@ -971,6 +971,36 @@ bool AP_AHRS::airspeed_vector_true(Vector3f &vec) const
|
|||||||
return false;
|
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
|
// return a synthetic airspeed estimate (one derived from sensors
|
||||||
// other than an actual airspeed sensor), if available. return
|
// other than an actual airspeed sensor), if available. return
|
||||||
// true if we have a synthetic airspeed. ret will not be modified
|
// true if we have a synthetic airspeed. ret will not be modified
|
||||||
|
@ -155,6 +155,10 @@ public:
|
|||||||
// returns false if estimate is unavailable
|
// returns false if estimate is unavailable
|
||||||
bool airspeed_vector_true(Vector3f &vec) const;
|
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
|
// return true if airspeed comes from an airspeed sensor, as
|
||||||
// opposed to an IMU estimate
|
// opposed to an IMU estimate
|
||||||
bool airspeed_sensor_enabled(void) const;
|
bool airspeed_sensor_enabled(void) const;
|
||||||
|
Loading…
Reference in New Issue
Block a user