AP_Baro_SITL.cpp 4.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133
  1. #include <AP_HAL/AP_HAL.h>
  2. #include <AP_Vehicle/AP_Vehicle_Type.h>
  3. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  4. #include "AP_Baro_SITL.h"
  5. extern const AP_HAL::HAL& hal;
  6. /*
  7. constructor - registers instance at top Baro driver
  8. */
  9. AP_Baro_SITL::AP_Baro_SITL(AP_Baro &baro) :
  10. _sitl(AP::sitl()),
  11. _has_sample(false),
  12. AP_Baro_Backend(baro)
  13. {
  14. if (_sitl != nullptr) {
  15. _instance = _frontend.register_sensor();
  16. #if APM_BUILD_TYPE(APM_BUILD_ArduSub)
  17. _frontend.set_type(_instance, AP_Baro::BARO_TYPE_WATER);
  18. #endif
  19. hal.scheduler->register_timer_process(FUNCTOR_BIND(this, &AP_Baro_SITL::_timer, void));
  20. }
  21. }
  22. // adjust for board temperature
  23. void AP_Baro_SITL::temperature_adjustment(float &p, float &T)
  24. {
  25. const float tsec = AP_HAL::millis() * 0.001f;
  26. const float T0 = _sitl->temp_start;
  27. const float T1 = _sitl->temp_flight;
  28. const float tconst = _sitl->temp_tconst;
  29. const float baro_factor = _sitl->temp_baro_factor;
  30. const float Tzero = 30.0f; // start baro adjustment at 30C
  31. T = T1 - (T1 - T0) * expf(-tsec / tconst);
  32. if (is_positive(baro_factor)) {
  33. // this produces a pressure change with temperature that
  34. // closely matches what has been observed with a ICM-20789
  35. // barometer. A typical factor is 1.2.
  36. p -= powf(MAX(T - Tzero, 0), baro_factor);
  37. }
  38. }
  39. void AP_Baro_SITL::_timer()
  40. {
  41. // 100Hz
  42. const uint32_t now = AP_HAL::millis();
  43. if ((now - _last_sample_time) < 10) {
  44. return;
  45. }
  46. _last_sample_time = now;
  47. float sim_alt = _sitl->state.altitude;
  48. if (_sitl->baro_disable) {
  49. // barometer is disabled
  50. return;
  51. }
  52. sim_alt += _sitl->baro_drift * now / 1000.0f;
  53. sim_alt += _sitl->baro_noise * rand_float();
  54. // add baro glitch
  55. sim_alt += _sitl->baro_glitch;
  56. // add delay
  57. uint32_t best_time_delta = 200; // initialise large time representing buffer entry closest to current time - delay.
  58. uint8_t best_index = 0; // initialise number representing the index of the entry in buffer closest to delay.
  59. // storing data from sensor to buffer
  60. if (now - _last_store_time >= 10) { // store data every 10 ms.
  61. _last_store_time = now;
  62. if (_store_index > _buffer_length - 1) { // reset buffer index if index greater than size of buffer
  63. _store_index = 0;
  64. }
  65. _buffer[_store_index].data = sim_alt; // add data to current index
  66. _buffer[_store_index].time = _last_store_time; // add time_stamp to current index
  67. _store_index = _store_index + 1; // increment index
  68. }
  69. // return delayed measurement
  70. const uint32_t delayed_time = now - _sitl->baro_delay; // get time corresponding to delay
  71. // find data corresponding to delayed time in buffer
  72. for (uint8_t i = 0; i <= _buffer_length - 1; i++) {
  73. // find difference between delayed time and time stamp in buffer
  74. uint32_t time_delta = abs(
  75. (int32_t)(delayed_time - _buffer[i].time));
  76. // if this difference is smaller than last delta, store this time
  77. if (time_delta < best_time_delta) {
  78. best_index = i;
  79. best_time_delta = time_delta;
  80. }
  81. }
  82. if (best_time_delta < 200) { // only output stored state if < 200 msec retrieval error
  83. sim_alt = _buffer[best_index].data;
  84. }
  85. #if !APM_BUILD_TYPE(APM_BUILD_ArduSub)
  86. float sigma, delta, theta;
  87. AP_Baro::SimpleAtmosphere(sim_alt * 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. temperature_adjustment(p, T);
  91. #else
  92. float rho, delta, theta;
  93. AP_Baro::SimpleUnderWaterAtmosphere(-sim_alt * 0.001f, rho, delta, theta);
  94. float p = SSL_AIR_PRESSURE * delta;
  95. float T = 303.16f * theta - C_TO_KELVIN; // Assume 30 degrees at sea level - converted to degrees Kelvin
  96. #endif
  97. _recent_press = p;
  98. _recent_temp = T;
  99. _has_sample = true;
  100. }
  101. // Read the sensor
  102. void AP_Baro_SITL::update(void)
  103. {
  104. if (!_has_sample) {
  105. return;
  106. }
  107. WITH_SEMAPHORE(_sem);
  108. _copy_to_frontend(_instance, _recent_press, _recent_temp);
  109. _has_sample = false;
  110. }
  111. #endif // CONFIG_HAL_BOARD