AP_Baro: read temperature from AP_Airspeed singleton

This commit is contained in:
DOMINATOR\Eugene 2018-11-16 18:16:50 +02:00 committed by Andrew Tridgell
parent c81f9e6baa
commit c56188d081
1 changed files with 14 additions and 3 deletions

View File

@ -382,9 +382,20 @@ float AP_Baro::get_external_temperature(const uint8_t instance) const
if (_last_external_temperature_ms != 0 && AP_HAL::millis() - _last_external_temperature_ms < 10000) {
return _external_temperature;
}
// if we don't have an external temperature then use the minimum
// of the barometer temperature and 35 degrees C. The reason for
// not just using the baro temperature is it tends to read high,
// if we don't have an external temperature then try to use temperature
// from the airspeed sensor
AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
if (airspeed != nullptr) {
float temperature;
if (airspeed->healthy() && airspeed->get_temperature(temperature)) {
return temperature;
}
}
// if we don't have an external temperature and airspeed temperature
// then use the minimum of the barometer temperature and 35 degrees C.
// The reason for not just using the baro temperature is it tends to read high,
// often 30 degrees above the actual temperature. That means the
// EAS2TAS tends to be off by quite a large margin, as well as
// the calculation of altitude difference betweeen two pressures