mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-04 12:43:58 -04:00
AP_Airspeed: make C_TO_KELVIN a function macro; create KELVIN_TO_C
These are in celsius
This commit is contained in:
parent
e988bf9046
commit
3969d6d56f
@ -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;
|
||||
|
@ -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();
|
||||
|
Loading…
Reference in New Issue
Block a user