mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
AP_Baro : Fixed bug in temperature units in AP_Baro_HIL
This commit is contained in:
parent
ebebee4f06
commit
ba009e55e3
@ -70,7 +70,7 @@ void AP_Baro_HIL::setHIL(float altitude_msl)
|
||||
|
||||
SimpleAtmosphere(altitude_msl*0.001, sigma, delta, theta);
|
||||
float p = p0 * delta;
|
||||
float T = 30 * theta;
|
||||
float T = 303.16 * theta - 273.16; // Assume 30 degrees at sea level - converted to degrees Kelvin
|
||||
|
||||
_count++;
|
||||
_pressure_sum += p;
|
||||
|
Loading…
Reference in New Issue
Block a user