AP_Baro: Avoid returning 0.0f for EAS2TAS
This commit is contained in:
parent
72440e2af3
commit
c712e926d7
@ -319,7 +319,11 @@ float AP_Baro::get_EAS2TAS(void)
|
|||||||
// provides a more consistent reading then trying to estimate a complete
|
// provides a more consistent reading then trying to estimate a complete
|
||||||
// ISA model atmosphere
|
// ISA model atmosphere
|
||||||
float tempK = get_ground_temperature() + C_TO_KELVIN - ISA_LAPSE_RATE * altitude;
|
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;
|
_last_altitude_EAS2TAS = altitude;
|
||||||
return _EAS2TAS;
|
return _EAS2TAS;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user