mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AP_Baro: Use C_TO_KELVIN
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
f3d6d8e236
commit
f22f053c83
@ -88,7 +88,7 @@ void AP_Baro::setHIL(float altitude_msl)
|
||||
|
||||
SimpleAtmosphere(altitude_msl*0.001f, sigma, delta, theta);
|
||||
float p = p0 * delta;
|
||||
float T = 303.16f * theta - 273.16f; // Assume 30 degrees at sea level - converted to degrees Kelvin
|
||||
float T = 303.16f * theta - C_TO_KELVIN; // Assume 30 degrees at sea level - converted to degrees Kelvin
|
||||
|
||||
_hil.pressure = p;
|
||||
_hil.temperature = T;
|
||||
|
@ -105,14 +105,14 @@ void AP_Baro_SITL::_timer()
|
||||
|
||||
AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta);
|
||||
float p = p0 * delta;
|
||||
float T = 303.16f * theta - 273.16f; // Assume 30 degrees at sea level - converted to degrees Kelvin
|
||||
float T = 303.16f * theta - C_TO_KELVIN; // Assume 30 degrees at sea level - converted to degrees Kelvin
|
||||
|
||||
temperature_adjustment(p, T);
|
||||
#else
|
||||
float rho, delta, theta;
|
||||
AP_Baro::SimpleUnderWaterAtmosphere(-sim_alt * 0.001f, rho, delta, theta);
|
||||
float p = p0 * delta;
|
||||
float T = 303.16f * theta - 273.16f; // Assume 30 degrees at sea level - converted to degrees Kelvin
|
||||
float T = 303.16f * theta - C_TO_KELVIN; // Assume 30 degrees at sea level - converted to degrees Kelvin
|
||||
#endif
|
||||
|
||||
_recent_press = p;
|
||||
|
@ -82,7 +82,7 @@ void AP_Baro_UAVCAN::handle_baro_msg(float pressure, float temperature)
|
||||
{
|
||||
if (_sem_baro->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
_pressure = pressure;
|
||||
_temperature = temperature - 273.15f;
|
||||
_temperature = temperature - C_TO_KELVIN;
|
||||
_last_timestamp = AP_HAL::micros64();
|
||||
_sem_baro->give();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user