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