AP_Baro_HIL.cpp 4.1 KB

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