APM:Libraries
AP_Baro_HIL.cpp
Go to the documentation of this file.
1 #include "AP_Baro_HIL.h"
2 
3 #include <AP_HAL/AP_HAL.h>
4 
5 extern const AP_HAL::HAL& hal;
6 
8  AP_Baro_Backend(baro)
9 {
11 }
12 
13 // ==========================================================================
14 // based on tables.cpp from http://www.pdas.com/atmosdownload.html
15 
16 /*
17  Compute the temperature, density, and pressure in the standard atmosphere
18  Correct to 20 km. Only approximate thereafter.
19 */
21  const float alt, // geometric altitude, km.
22  float& sigma, // density/sea-level standard density
23  float& delta, // pressure/sea-level standard pressure
24  float& theta) // temperature/sea-level standard temperature
25 {
26  const float REARTH = 6369.0f; // radius of the Earth (km)
27  const float GMR = 34.163195f; // gas constant
28  float h=alt*REARTH/(alt+REARTH); // geometric to geopotential altitude
29 
30  if (h < 11.0f) {
31  // Troposphere
32  theta = (SSL_AIR_TEMPERATURE - 6.5f * h) / SSL_AIR_TEMPERATURE;
33  delta = powf(theta, GMR / 6.5f);
34  } else {
35  // Stratosphere
36  theta = 216.65f / SSL_AIR_TEMPERATURE;
37  delta = 0.2233611f * expf(-GMR * (h - 11.0f) / 216.65f);
38  }
39 
40  sigma = delta/theta;
41 }
42 
44  float alt, // depth, km.
45  float& rho, // density/sea-level
46  float& delta, // pressure/sea-level standard pressure
47  float& theta) // temperature/sea-level standard temperature
48 {
49  // Values and equations based on:
50  // https://en.wikipedia.org/wiki/Standard_sea_level
51  const float seaDensity = 1.024f; // g/cm3
52  const float maxSeaDensity = 1.028f; // g/cm3
53  const float pAC = maxSeaDensity - seaDensity; // pycnocline angular coefficient
54 
55  // From: https://www.windows2universe.org/earth/Water/density.html
56  rho = seaDensity;
57  if (alt < 1.0f) {
58  // inside pycnocline
59  rho += pAC*alt;
60  } else {
61  rho += pAC;
62  }
63  rho = rho/seaDensity;
64 
65  // From: https://www.grc.nasa.gov/www/k-12/WindTunnel/Activities/fluid_pressure.html
66  // \f$P = \rho (kg) \cdot gravity (m/s2) \cdot depth (m)\f$
67  // \f$P_{atmosphere} = 101.325 kPa\f$
68  // \f$P_{total} = P_{atmosphere} + P_{fluid}\f$
69  delta = (SSL_AIR_PRESSURE + (seaDensity * 1e3) * GRAVITY_MSS * (alt * 1e3)) / SSL_AIR_PRESSURE;
70 
71  // From: http://residualanalysis.blogspot.com.br/2010/02/temperature-of-ocean-water-at-given.html
72  // \f$T(D)\f$ Temperature underwater at given temperature
73  // \f$S\f$ Surface temperature at the surface
74  // \f$T(D)\approx\frac{S}{1.8 \cdot 10^{-4} \cdot S \cdot T + 1}\f$
75  const float seaTempSurface = 15.0f; // Celsius
76  const float S = seaTempSurface * 0.338f;
77  theta = 1.0f / ((1.8e-4) * S * (alt * 1e3) + 1.0f);
78 }
79 
80 /*
81  convert an altitude in meters above sea level to a presssure and temperature
82  */
83 void AP_Baro::setHIL(float altitude_msl)
84 {
85  float sigma, delta, theta;
86 
87  SimpleAtmosphere(altitude_msl*0.001f, sigma, delta, theta);
88  float p = SSL_AIR_PRESSURE * delta;
89  float T = 303.16f * theta - C_TO_KELVIN; // Assume 30 degrees at sea level - converted to degrees Kelvin
90 
91  _hil.pressure = p;
92  _hil.temperature = T;
93  _hil.updated = true;
94 }
95 
96 /*
97  set HIL pressure and temperature for an instance
98  */
99 void AP_Baro::setHIL(uint8_t instance, float pressure, float temperature, float altitude, float climb_rate, uint32_t last_update_ms)
100 {
101  if (instance >= _num_sensors) {
102  // invalid
103  return;
104  }
105  _hil.pressure = pressure;
106  _hil.temperature = temperature;
107  _hil.altitude = altitude;
108  _hil.climb_rate = climb_rate;
109  _hil.updated = true;
110  _hil.have_alt = true;
111 
112  if (last_update_ms != 0) {
113  _hil.last_update_ms = last_update_ms;
114  _hil.have_last_update = true;
115  }
116 }
117 
118 // Read the sensor
120 {
121  if (_frontend._hil.updated) {
122  _frontend._hil.updated = false;
124  }
125 }
static void SimpleAtmosphere(const float alt, float &sigma, float &delta, float &theta)
Definition: AP_Baro_HIL.cpp:20
#define C_TO_KELVIN
Definition: definitions.h:74
void _copy_to_frontend(uint8_t instance, float pressure, float temperature)
uint8_t register_sensor(void)
Definition: AP_Baro.cpp:705
struct AP_Baro::@7 _hil
void update(void)
AP_Baro_HIL(AP_Baro &baro)
Definition: AP_Baro_HIL.cpp:7
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
static int8_t delta
Definition: RCOutput.cpp:21
static void SimpleUnderWaterAtmosphere(float alt, float &rho, float &delta, float &theta)
Definition: AP_Baro_HIL.cpp:43
float temperature
Definition: Airspeed.cpp:32
uint8_t _instance
Definition: AP_Baro_HIL.h:16
AP_Baro & _frontend
#define GRAVITY_MSS
Definition: definitions.h:47
#define f(i)
static AP_Baro baro
Definition: ModuleTest.cpp:18
#define SSL_AIR_PRESSURE
Definition: definitions.h:83
float temperature
Definition: AP_Baro.h:144
#define SSL_AIR_TEMPERATURE
Definition: definitions.h:84
float pressure
Definition: AP_Baro.h:143
bool updated
Definition: AP_Baro.h:148
void setHIL(float altitude_msl)
Definition: AP_Baro_HIL.cpp:83