Plane: HIGH_Latency2 check get_temperature return and return INT8_MIN

This commit is contained in:
Josh Henderson 2021-10-12 00:15:16 -04:00 committed by Andrew Tridgell
parent 893354ccfe
commit 8af299f978
1 changed files with 5 additions and 5 deletions

View File

@ -1418,11 +1418,11 @@ int8_t GCS_MAVLINK_Plane::high_latency_air_temperature() const
{
// return units are degC
AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
float air_temperature = 0;
if (airspeed != nullptr &&
airspeed->enabled()) {
airspeed->get_temperature(air_temperature);
float air_temperature;
if (airspeed != nullptr && airspeed->enabled() && airspeed->get_temperature(air_temperature)) {
return air_temperature;
}
return air_temperature;
return INT8_MIN;
}
#endif // HAL_HIGH_LATENCY2_ENABLED