AP_AHRS: Add accessor function for body frame airspeed vector

This commit is contained in:
Paul Riseborough 2020-11-21 08:40:19 +11:00 committed by Andrew Tridgell
parent b372d62f35
commit 3a0105fcc3
3 changed files with 35 additions and 0 deletions

View File

@ -265,6 +265,12 @@ public:
return true;
}
// return estimate of true airspeed vector in body frame in m/s
// returns false if estimate is unavailable
virtual bool airspeed_vector_true(Vector3f &vec) const WARN_IF_UNUSED {
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

@ -561,6 +561,31 @@ bool AP_AHRS_NavEKF::airspeed_estimate(float &airspeed_ret) const
return AP_AHRS_DCM::airspeed_estimate(get_active_airspeed_index(), airspeed_ret);
}
// return estimate of true airspeed vector in body frame in m/s
// returns false if estimate is unavailable
bool AP_AHRS_NavEKF::airspeed_vector_true(Vector3f &vec) const
{
switch (active_EKF_type()) {
case EKFType::NONE:
break;
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.getAirSpdVec(-1, vec);
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.getAirSpdVec(-1, vec);
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
break;
#endif
}
return false;
}
// true if compass is being used
bool AP_AHRS_NavEKF::use_compass(void)
{

View File

@ -96,6 +96,10 @@ public:
// if we have an estimate
bool airspeed_estimate(float &airspeed_ret) const override;
// return estimate of true airspeed vector in body frame in m/s
// returns false if estimate is unavailable
bool airspeed_vector_true(Vector3f &vec) const override;
// true if compass is being used
bool use_compass() override;