AP_Airspeed: make C_TO_KELVIN a function macro; create KELVIN_TO_C

These are in celsius
This commit is contained in:
Peter Barker 2022-01-12 23:03:23 +11:00 committed by Peter Barker
parent e988bf9046
commit 3969d6d56f
2 changed files with 2 additions and 2 deletions

View File

@ -237,7 +237,7 @@ float AP_Airspeed_SDP3X::_correct_pressure(float press)
temperature = 25;
}
float rho_air = baro_pressure / (ISA_GAS_CONSTANT * (temperature + C_TO_KELVIN));
float rho_air = baro_pressure / (ISA_GAS_CONSTANT * C_TO_KELVIN(temperature));
if (!is_positive(rho_air)) {
// bad pressure
return press;

View File

@ -121,7 +121,7 @@ void AP_Airspeed_UAVCAN::handle_airspeed(AP_UAVCAN* ap_uavcan, uint8_t node_id,
driver->_pressure = cb.msg->differential_pressure;
if (!isnan(cb.msg->static_air_temperature) &&
cb.msg->static_air_temperature > 0) {
driver->_temperature = cb.msg->static_air_temperature - C_TO_KELVIN;
driver->_temperature = KELVIN_TO_C(cb.msg->static_air_temperature);
driver->_have_temperature = true;
}
driver->_last_sample_time_ms = AP_HAL::millis();