mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Baro: moved constants to AP_Math/definitions.h
This commit is contained in:
parent
ee1fea55ce
commit
5846558b0e
@ -45,11 +45,6 @@
|
||||
#include "AP_Baro_UAVCAN.h"
|
||||
#endif
|
||||
|
||||
#define C_TO_KELVIN 273.15f
|
||||
// Gas Constant is from Aerodynamics for Engineering Students, Third Edition, E.L.Houghton and N.B.Carruthers
|
||||
#define ISA_GAS_CONSTANT 287.26f
|
||||
#define ISA_LAPSE_RATE 0.0065f
|
||||
|
||||
#define INTERNAL_TEMPERATURE_CLAMP 35.0f
|
||||
|
||||
|
||||
@ -288,7 +283,7 @@ float AP_Baro::get_EAS2TAS(void)
|
||||
// provides a more consistent reading then trying to estimate a complete
|
||||
// ISA model atmosphere
|
||||
float tempK = get_ground_temperature() + C_TO_KELVIN - ISA_LAPSE_RATE * altitude;
|
||||
_EAS2TAS = safe_sqrt(1.225f / ((float)get_pressure() / (ISA_GAS_CONSTANT * tempK)));
|
||||
_EAS2TAS = safe_sqrt(AIR_DENSITY_SEA_LEVEL / ((float)get_pressure() / (ISA_GAS_CONSTANT * tempK)));
|
||||
_last_altitude_EAS2TAS = altitude;
|
||||
return _EAS2TAS;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user