26 const float REARTH = 6369.0f;
27 const float GMR = 34.163195f;
28 float h=alt*REARTH/(alt+REARTH);
33 delta = powf(theta, GMR / 6.5
f);
37 delta = 0.2233611f * expf(-GMR * (h - 11.0
f) / 216.65
f);
51 const float seaDensity = 1.024f;
52 const float maxSeaDensity = 1.028f;
53 const float pAC = maxSeaDensity - seaDensity;
75 const float seaTempSurface = 15.0f;
76 const float S = seaTempSurface * 0.338f;
77 theta = 1.0f / ((1.8e-4) * S * (alt * 1e3) + 1.0f);
85 float sigma,
delta, theta;
87 SimpleAtmosphere(altitude_msl*0.001
f, sigma, delta, theta);
101 if (instance >= _num_sensors) {
105 _hil.pressure = pressure;
107 _hil.altitude = altitude;
108 _hil.climb_rate = climb_rate;
110 _hil.have_alt =
true;
112 if (last_update_ms != 0) {
113 _hil.last_update_ms = last_update_ms;
114 _hil.have_last_update =
true;
static void SimpleAtmosphere(const float alt, float &sigma, float &delta, float &theta)
void _copy_to_frontend(uint8_t instance, float pressure, float temperature)
uint8_t register_sensor(void)
AP_Baro_HIL(AP_Baro &baro)
static void SimpleUnderWaterAtmosphere(float alt, float &rho, float &delta, float &theta)
#define SSL_AIR_TEMPERATURE
void setHIL(float altitude_msl)