CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Baro/AP_Baro_SITL.cpp
Views: 1798
1
#include "AP_Baro_SITL.h"
2
3
#if AP_SIM_BARO_ENABLED
4
5
#include <AP_HAL/AP_HAL.h>
6
#include <AP_Vehicle/AP_Vehicle_Type.h>
7
8
extern const AP_HAL::HAL& hal;
9
10
/*
11
constructor - registers instance at top Baro driver
12
*/
13
AP_Baro_SITL::AP_Baro_SITL(AP_Baro &baro) :
14
AP_Baro_Backend(baro),
15
_sitl(AP::sitl()),
16
_has_sample(false)
17
{
18
if (_sitl != nullptr) {
19
_instance = _frontend.register_sensor();
20
#if APM_BUILD_TYPE(APM_BUILD_ArduSub)
21
_frontend.set_type(_instance, AP_Baro::BARO_TYPE_WATER);
22
#endif
23
set_bus_id(_instance, AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_SITL, 0, _instance, DEVTYPE_BARO_SITL));
24
hal.scheduler->register_timer_process(FUNCTOR_BIND(this, &AP_Baro_SITL::_timer, void));
25
}
26
}
27
28
// adjust for board temperature warmup on start-up
29
void AP_Baro_SITL::temperature_adjustment(float &p, float &T)
30
{
31
const float tsec = AP_HAL::millis() * 0.001f;
32
const float T_sensor = T + AP::sitl()->temp_board_offset;
33
const float tconst = AP::sitl()->temp_tconst;
34
if (tsec < 23 * tconst) { // time which past the equation below equals T_sensor within approx. 1E-9
35
const float T0 = AP::sitl()->temp_start;
36
T = T_sensor - (T_sensor - T0) * expf(-tsec / tconst);
37
}
38
else {
39
T = T_sensor;
40
}
41
42
const float baro_factor = AP::sitl()->temp_baro_factor;
43
const float Tzero = 30.0f; // start baro adjustment at 30C
44
if (is_positive(baro_factor)) {
45
// this produces a pressure change with temperature that
46
// closely matches what has been observed with a ICM-20789
47
// barometer. A typical factor is 1.2.
48
p -= powf(MAX(T - Tzero, 0), baro_factor);
49
}
50
}
51
52
void AP_Baro_SITL::_timer()
53
{
54
55
// 100Hz
56
const uint32_t now = AP_HAL::millis();
57
if ((now - _last_sample_time) < 10) {
58
return;
59
}
60
_last_sample_time = now;
61
62
float sim_alt = _sitl->state.altitude;
63
64
if (_sitl->baro[_instance].disable) {
65
// barometer is disabled
66
return;
67
}
68
69
const auto drift_delta_t_ms = now - last_drift_delta_t_ms;
70
last_drift_delta_t_ms = now;
71
total_alt_drift += _sitl->baro[_instance].drift * drift_delta_t_ms * 0.001f;
72
73
sim_alt += total_alt_drift;
74
sim_alt += _sitl->baro[_instance].noise * rand_float();
75
76
// add baro glitch
77
sim_alt += _sitl->baro[_instance].glitch;
78
79
// add delay
80
uint32_t best_time_delta = 200; // initialise large time representing buffer entry closest to current time - delay.
81
uint8_t best_index = 0; // initialise number representing the index of the entry in buffer closest to delay.
82
83
// storing data from sensor to buffer
84
if (now - _last_store_time >= 10) { // store data every 10 ms.
85
_last_store_time = now;
86
if (_store_index > _buffer_length - 1) { // reset buffer index if index greater than size of buffer
87
_store_index = 0;
88
}
89
90
// if freezed barometer, report altitude to last recorded altitude
91
if (_sitl->baro[_instance].freeze == 1) {
92
sim_alt = _last_altitude;
93
} else {
94
_last_altitude = sim_alt;
95
}
96
97
_buffer[_store_index].data = sim_alt; // add data to current index
98
_buffer[_store_index].time = _last_store_time; // add time_stamp to current index
99
_store_index = _store_index + 1; // increment index
100
}
101
102
// return delayed measurement
103
const uint32_t delayed_time = now - _sitl->baro[_instance].delay; // get time corresponding to delay
104
105
// find data corresponding to delayed time in buffer
106
for (uint8_t i = 0; i <= _buffer_length - 1; i++) {
107
// find difference between delayed time and time stamp in buffer
108
uint32_t time_delta = abs(
109
(int32_t)(delayed_time - _buffer[i].time));
110
// if this difference is smaller than last delta, store this time
111
if (time_delta < best_time_delta) {
112
best_index = i;
113
best_time_delta = time_delta;
114
}
115
}
116
if (best_time_delta < 200) { // only output stored state if < 200 msec retrieval error
117
sim_alt = _buffer[best_index].data;
118
}
119
120
#if !APM_BUILD_TYPE(APM_BUILD_ArduSub)
121
float p, T_K;
122
AP_Baro::get_pressure_temperature_for_alt_amsl(sim_alt, p, T_K);
123
float T = KELVIN_TO_C(T_K);
124
temperature_adjustment(p, T);
125
#else
126
float rho, delta, theta;
127
AP_Baro::SimpleUnderWaterAtmosphere(-sim_alt * 0.001f, rho, delta, theta);
128
float p = SSL_AIR_PRESSURE * delta;
129
float T = KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta);
130
#endif
131
132
// add in correction for wind effects
133
p += wind_pressure_correction(_instance);
134
135
_recent_press = p;
136
_recent_temp = T;
137
_has_sample = true;
138
}
139
140
// unhealthy if baro is turned off or beyond supported instances
141
bool AP_Baro_SITL::healthy(uint8_t instance)
142
{
143
return _last_sample_time != 0 && !_sitl->baro[instance].disable;
144
}
145
146
// Read the sensor
147
void AP_Baro_SITL::update(void)
148
{
149
if (!_has_sample) {
150
return;
151
}
152
153
WITH_SEMAPHORE(_sem);
154
_copy_to_frontend(_instance, _recent_press, _recent_temp);
155
_has_sample = false;
156
}
157
158
/*
159
return pressure correction for wind based on SIM_BARO_WCF parameters
160
*/
161
float AP_Baro_SITL::wind_pressure_correction(uint8_t instance)
162
{
163
const auto &bp = AP::sitl()->baro[instance];
164
165
// correct for static pressure position errors
166
const Vector3f &airspeed_vec_bf = AP::sitl()->state.velocity_air_bf;
167
168
float error = 0.0;
169
const float sqx = sq(airspeed_vec_bf.x);
170
const float sqy = sq(airspeed_vec_bf.y);
171
const float sqz = sq(airspeed_vec_bf.z);
172
173
if (is_positive(airspeed_vec_bf.x)) {
174
error += bp.wcof_xp * sqx;
175
} else {
176
error += bp.wcof_xn * sqx;
177
}
178
if (is_positive(airspeed_vec_bf.y)) {
179
error += bp.wcof_yp * sqy;
180
} else {
181
error += bp.wcof_yn * sqy;
182
}
183
if (is_positive(airspeed_vec_bf.z)) {
184
error += bp.wcof_zp * sqz;
185
} else {
186
error += bp.wcof_zn * sqz;
187
}
188
189
return error * 0.5 * SSL_AIR_DENSITY * AP::baro()._get_air_density_ratio();
190
}
191
192
#endif // AP_SIM_BARO_ENABLED
193
194