AP_Baro: Avoid returning 0.0f for EAS2TAS

This commit is contained in:
Michael du Breuil 2018-11-05 16:14:21 -07:00 committed by Andrew Tridgell
parent 72440e2af3
commit c712e926d7
1 changed files with 5 additions and 1 deletions

View File

@ -319,7 +319,11 @@ float AP_Baro::get_EAS2TAS(void)
// provides a more consistent reading then trying to estimate a complete
// ISA model atmosphere
float tempK = get_ground_temperature() + C_TO_KELVIN - ISA_LAPSE_RATE * altitude;
_EAS2TAS = safe_sqrt(SSL_AIR_DENSITY / ((float)get_pressure() / (ISA_GAS_CONSTANT * tempK)));
const float eas2tas_squared = SSL_AIR_DENSITY / ((float)get_pressure() / (ISA_GAS_CONSTANT * tempK));
if (!is_positive(eas2tas_squared)) {
return 1.0;
}
_EAS2TAS = sqrtf(eas2tas_squared);
_last_altitude_EAS2TAS = altitude;
return _EAS2TAS;
}