mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: prevent use of uninitialised EAS2TAS
This commit is contained in:
parent
86b779f3c7
commit
b161bdd6a9
|
@ -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;
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue