sitl_airspeed.cpp 4.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110
  1. /*
  2. SITL handling
  3. This simulates an analog airspeed sensor
  4. Andrew Tridgell November 2011
  5. */
  6. #include <AP_HAL/AP_HAL.h>
  7. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  8. #include "AP_HAL_SITL.h"
  9. #include "AP_HAL_SITL_Namespace.h"
  10. #include "HAL_SITL_Class.h"
  11. #include "SITL_State.h"
  12. #include <SITL/SITL.h>
  13. #include <AP_Math/AP_Math.h>
  14. extern const AP_HAL::HAL& hal;
  15. using namespace HALSITL;
  16. /*
  17. convert airspeed in m/s to an airspeed sensor value
  18. */
  19. void SITL_State::_update_airspeed(float airspeed)
  20. {
  21. const float airspeed_ratio = 1.9936f;
  22. const float airspeed_offset = 2013.0f;
  23. float airspeed2 = airspeed;
  24. // Check sensor failure
  25. airspeed = is_zero(_sitl->arspd_fail) ? airspeed : _sitl->arspd_fail;
  26. airspeed2 = is_zero(_sitl->arspd2_fail) ? airspeed2 : _sitl->arspd2_fail;
  27. // Add noise
  28. airspeed = airspeed + (_sitl->arspd_noise * rand_float());
  29. airspeed2 = airspeed2 + (_sitl->arspd_noise * rand_float());
  30. if (!is_zero(_sitl->arspd_fail_pressure)) {
  31. // compute a realistic pressure report given some level of trapper air pressure in the tube and our current altitude
  32. // algorithm taken from https://en.wikipedia.org/wiki/Calibrated_airspeed#Calculation_from_impact_pressure
  33. float tube_pressure = fabsf(_sitl->arspd_fail_pressure - _barometer->get_pressure() + _sitl->arspd_fail_pitot_pressure);
  34. airspeed = 340.29409348 * sqrt(5 * (pow((tube_pressure / SSL_AIR_PRESSURE + 1), 2.0/7.0) - 1.0));
  35. }
  36. if (!is_zero(_sitl->arspd2_fail_pressure)) {
  37. // compute a realistic pressure report given some level of trapper air pressure in the tube and our current altitude
  38. // algorithm taken from https://en.wikipedia.org/wiki/Calibrated_airspeed#Calculation_from_impact_pressure
  39. float tube_pressure = fabsf(_sitl->arspd2_fail_pressure - _barometer->get_pressure() + _sitl->arspd2_fail_pitot_pressure);
  40. airspeed2 = 340.29409348 * sqrt(5 * (pow((tube_pressure / SSL_AIR_PRESSURE + 1), 2.0/7.0) - 1.0));
  41. }
  42. float airspeed_pressure = (airspeed * airspeed) / airspeed_ratio;
  43. float airspeed2_pressure = (airspeed2 * airspeed2) / airspeed_ratio;
  44. // flip sign here for simulating reversed pitot/static connections
  45. if (_sitl->arspd_signflip) airspeed_pressure *= -1;
  46. if (_sitl->arspd_signflip) airspeed2_pressure *= -1;
  47. float airspeed_raw = airspeed_pressure + airspeed_offset;
  48. float airspeed2_raw = airspeed2_pressure + airspeed_offset;
  49. if (airspeed_raw / 4 > 0xFFFF) {
  50. airspeed_pin_value = 0xFFFF;
  51. return;
  52. }
  53. if (airspeed2_raw / 4 > 0xFFFF) {
  54. airspeed_2_pin_value = 0xFFFF;
  55. return;
  56. }
  57. // add delay
  58. const uint32_t now = AP_HAL::millis();
  59. uint32_t best_time_delta_wind = 200; // initialise large time representing buffer entry closest to current time - delay.
  60. uint8_t best_index_wind = 0; // initialise number representing the index of the entry in buffer closest to delay.
  61. // storing data from sensor to buffer
  62. if (now - last_store_time_wind >= 10) { // store data every 10 ms.
  63. last_store_time_wind = now;
  64. if (store_index_wind > wind_buffer_length - 1) { // reset buffer index if index greater than size of buffer
  65. store_index_wind = 0;
  66. }
  67. buffer_wind[store_index_wind].data = airspeed_raw; // add data to current index
  68. buffer_wind[store_index_wind].time = last_store_time_wind; // add time to current index
  69. buffer_wind_2[store_index_wind].data = airspeed2_raw; // add data to current index
  70. buffer_wind_2[store_index_wind].time = last_store_time_wind; // add time to current index
  71. store_index_wind = store_index_wind + 1; // increment index
  72. }
  73. // return delayed measurement
  74. delayed_time_wind = now - _sitl->wind_delay; // get time corresponding to delay
  75. // find data corresponding to delayed time in buffer
  76. for (uint8_t i = 0; i <= wind_buffer_length - 1; i++) {
  77. // find difference between delayed time and time stamp in buffer
  78. time_delta_wind = abs(
  79. (int32_t)(delayed_time_wind - buffer_wind[i].time));
  80. // if this difference is smaller than last delta, store this time
  81. if (time_delta_wind < best_time_delta_wind) {
  82. best_index_wind = i;
  83. best_time_delta_wind = time_delta_wind;
  84. }
  85. }
  86. if (best_time_delta_wind < 200) { // only output stored state if < 200 msec retrieval error
  87. airspeed_raw = buffer_wind[best_index_wind].data;
  88. airspeed2_raw = buffer_wind_2[best_index_wind].data;
  89. }
  90. airspeed_pin_value = airspeed_raw / 4;
  91. airspeed_2_pin_value = airspeed2_raw / 4;
  92. }
  93. #endif