AP_AHRS: prevent use of uninitialised EAS2TAS

This commit is contained in:
Andrew Tridgell 2024-05-05 06:52:53 +10:00
parent 86b779f3c7
commit b161bdd6a9
2 changed files with 12 additions and 3 deletions

View File

@ -3559,6 +3559,17 @@ bool AP_AHRS::get_location_from_home_offset(Location &loc, const Vector3p &offse
return true;
}
/*
get EAS to TAS scaling
*/
float AP_AHRS::get_EAS2TAS(void) const
{
if (is_positive(state.EAS2TAS)) {
return state.EAS2TAS;
}
return 1.0;
}
// singleton instance
AP_AHRS *AP_AHRS::_singleton;

View File

@ -141,9 +141,7 @@ public:
*/
// get apparent to true airspeed ratio
float get_EAS2TAS(void) const {
return state.EAS2TAS;
}
float get_EAS2TAS(void) const;
// return an airspeed estimate if available. return true
// if we have an estimate