APM:Libraries
AP_Baro_SITL.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
3 
4 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
5 
6 #include "AP_Baro_SITL.h"
7 
8 extern const AP_HAL::HAL& hal;
9 
10 /*
11  constructor - registers instance at top Baro driver
12  */
14  _has_sample(false),
15  AP_Baro_Backend(baro)
16 {
18  if (_sitl != nullptr) {
20 #if APM_BUILD_TYPE(APM_BUILD_ArduSub)
22 #endif
24  }
25 }
26 
27 // adjust for board temperature
28 void AP_Baro_SITL::temperature_adjustment(float &p, float &T)
29 {
30  const float tsec = AP_HAL::millis() * 0.001f;
31  const float T0 = _sitl->temp_start;
32  const float T1 = _sitl->temp_flight;
33  const float tconst = _sitl->temp_tconst;
34  const float baro_factor = _sitl->temp_baro_factor;
35  const float Tzero = 30.0f; // start baro adjustment at 30C
36  T = T1 - (T1 - T0) * expf(-tsec / tconst);
37  if (is_positive(baro_factor)) {
38  // this produces a pressure change with temperature that
39  // closely matches what has been observed with a ICM-20789
40  // barometer. A typical factor is 1.2.
41  p -= powf(MAX(T - Tzero, 0), baro_factor);
42  }
43 }
44 
46 {
47 
48  // 100Hz
49  const uint32_t now = AP_HAL::millis();
50  if ((now - _last_sample_time) < 10) {
51  return;
52  }
53  _last_sample_time = now;
54 
55  float sim_alt = _sitl->state.altitude;
56 
57  if (_sitl->baro_disable) {
58  // barometer is disabled
59  return;
60  }
61 
62  sim_alt += _sitl->baro_drift * now / 1000.0f;
63  sim_alt += _sitl->baro_noise * rand_float();
64 
65  // add baro glitch
66  sim_alt += _sitl->baro_glitch;
67 
68  // add delay
69  uint32_t best_time_delta = 200; // initialise large time representing buffer entry closest to current time - delay.
70  uint8_t best_index = 0; // initialise number representing the index of the entry in buffer closest to delay.
71 
72  // storing data from sensor to buffer
73  if (now - _last_store_time >= 10) { // store data every 10 ms.
74  _last_store_time = now;
75  if (_store_index > _buffer_length - 1) { // reset buffer index if index greater than size of buffer
76  _store_index = 0;
77  }
78  _buffer[_store_index].data = sim_alt; // add data to current index
79  _buffer[_store_index].time = _last_store_time; // add time_stamp to current index
80  _store_index = _store_index + 1; // increment index
81  }
82 
83  // return delayed measurement
84  const uint32_t delayed_time = now - _sitl->baro_delay; // get time corresponding to delay
85 
86  // find data corresponding to delayed time in buffer
87  for (uint8_t i = 0; i <= _buffer_length - 1; i++) {
88  // find difference between delayed time and time stamp in buffer
89  uint32_t time_delta = abs(
90  (int32_t)(delayed_time - _buffer[i].time));
91  // if this difference is smaller than last delta, store this time
92  if (time_delta < best_time_delta) {
93  best_index = i;
94  best_time_delta = time_delta;
95  }
96  }
97  if (best_time_delta < 200) { // only output stored state if < 200 msec retrieval error
98  sim_alt = _buffer[best_index].data;
99  }
100 
101 #if !APM_BUILD_TYPE(APM_BUILD_ArduSub)
102  float sigma, delta, theta;
103 
104  AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta);
105  float p = SSL_AIR_PRESSURE * delta;
106  float T = 303.16f * theta - C_TO_KELVIN; // Assume 30 degrees at sea level - converted to degrees Kelvin
107 
109 #else
110  float rho, delta, theta;
111  AP_Baro::SimpleUnderWaterAtmosphere(-sim_alt * 0.001f, rho, delta, theta);
112  float p = SSL_AIR_PRESSURE * delta;
113  float T = 303.16f * theta - C_TO_KELVIN; // Assume 30 degrees at sea level - converted to degrees Kelvin
114 #endif
115 
116  _recent_press = p;
117  _recent_temp = T;
118  _has_sample = true;
119 }
120 
121 // Read the sensor
123 {
124  if (_sem->take_nonblocking()) {
125  if (!_has_sample) {
126  _sem->give();
127  return;
128  }
129 
131  _has_sample = false;
132  _sem->give();
133  }
134 }
135 
136 #endif // CONFIG_HAL_BOARD
AP_Baro_SITL(AP_Baro &)
AP_Int8 baro_disable
Definition: SITL.h:134
static AP_Param * find_object(const char *name)
Definition: AP_Param.cpp:939
void update() override
static void SimpleAtmosphere(const float alt, float &sigma, float &delta, float &theta)
Definition: AP_Baro_HIL.cpp:20
AP_Float baro_glitch
Definition: SITL.h:88
#define C_TO_KELVIN
Definition: definitions.h:74
VectorN< readings_baro, _buffer_length > _buffer
Definition: AP_Baro_SITL.h:31
void _copy_to_frontend(uint8_t instance, float pressure, float temperature)
uint8_t register_sensor(void)
Definition: AP_Baro.cpp:705
AP_HAL::Semaphore * _sem
bool is_positive(const T fVal1)
Definition: AP_Math.h:50
uint32_t _last_store_time
Definition: AP_Baro_SITL.h:29
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
static int8_t delta
Definition: RCOutput.cpp:21
#define FUNCTOR_BIND(obj, func, rettype,...)
Definition: functor.h:28
static void SimpleUnderWaterAtmosphere(float alt, float &rho, float &delta, float &theta)
Definition: AP_Baro_HIL.cpp:43
AP_Float temp_baro_factor
Definition: SITL.h:187
virtual bool take_nonblocking() WARN_IF_UNUSED=0
AP_Baro & _frontend
#define f(i)
float _recent_temp
Definition: AP_Baro_SITL.h:39
static AP_Baro baro
Definition: ModuleTest.cpp:18
uint32_t millis()
Definition: system.cpp:157
#define SSL_AIR_PRESSURE
Definition: definitions.h:83
AP_Float temp_tconst
Definition: SITL.h:186
float _recent_press
Definition: AP_Baro_SITL.h:40
AP_Float baro_noise
Definition: SITL.h:86
AP_Float temp_flight
Definition: SITL.h:185
virtual bool give()=0
void set_type(uint8_t instance, baro_type_t type)
Definition: AP_Baro.h:136
void temperature_adjustment(float &p, float &T)
AP_Float baro_drift
Definition: SITL.h:87
uint32_t _last_sample_time
Definition: AP_Baro_SITL.h:38
virtual void register_timer_process(AP_HAL::MemberProc)=0
static const uint8_t _buffer_length
Definition: AP_Baro_SITL.h:30
uint8_t _instance
Definition: AP_Baro_SITL.h:20
float rand_float(void)
Definition: AP_Math.cpp:224
AP_Float temp_start
Definition: SITL.h:184
bool _has_sample
Definition: AP_Baro_SITL.h:37
SITL::SITL * _sitl
Definition: AP_Baro_SITL.h:21
double altitude
Definition: SITL.h:15
AP_Int16 baro_delay
Definition: SITL.h:163
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
struct sitl_fdm state
Definition: SITL.h:71
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
uint8_t _store_index
Definition: AP_Baro_SITL.h:28