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_Airspeed/AP_Airspeed_SDP3X.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
/*
17
backend driver for airspeed from a I2C SDP3X sensor
18
19
with thanks to https://github.com/PX4/Firmware/blob/master/src/drivers/sdp3x_airspeed
20
*/
21
#include "AP_Airspeed_SDP3X.h"
22
23
#if AP_AIRSPEED_SDP3X_ENABLED
24
25
#include <GCS_MAVLink/GCS.h>
26
#include <AP_Baro/AP_Baro.h>
27
28
#include <stdio.h>
29
30
#define SDP3X_SCALE_TEMPERATURE 200.0f
31
32
#define SDP3XD0_I2C_ADDR 0x21
33
#define SDP3XD1_I2C_ADDR 0x22
34
#define SDP3XD2_I2C_ADDR 0x23
35
36
#define SDP3X_CONT_MEAS_AVG_MODE 0x3615
37
#define SDP3X_CONT_MEAS_STOP 0x3FF9
38
39
#define SDP3X_SCALE_PRESSURE_SDP31 60
40
#define SDP3X_SCALE_PRESSURE_SDP32 240
41
#define SDP3X_SCALE_PRESSURE_SDP33 20
42
43
extern const AP_HAL::HAL &hal;
44
45
/*
46
send a 16 bit command code
47
*/
48
bool AP_Airspeed_SDP3X::_send_command(uint16_t cmd)
49
{
50
uint8_t b[2] {uint8_t(cmd >> 8), uint8_t(cmd & 0xFF)};
51
return _dev->transfer(b, 2, nullptr, 0);
52
}
53
54
// probe and initialise the sensor
55
bool AP_Airspeed_SDP3X::init()
56
{
57
const uint8_t addresses[3] = { SDP3XD0_I2C_ADDR,
58
SDP3XD1_I2C_ADDR,
59
SDP3XD2_I2C_ADDR
60
};
61
bool found = false;
62
bool ret = false;
63
64
for (uint8_t i=0; i<ARRAY_SIZE(addresses) && !found; i++) {
65
_dev = hal.i2c_mgr->get_device(get_bus(), addresses[i]);
66
if (!_dev) {
67
continue;
68
}
69
_dev->get_semaphore()->take_blocking();
70
71
// lots of retries during probe
72
_dev->set_retries(10);
73
74
// stop continuous average mode
75
if (!_send_command(SDP3X_CONT_MEAS_STOP)) {
76
_dev->get_semaphore()->give();
77
continue;
78
}
79
80
// these delays are needed for reliable operation
81
_dev->get_semaphore()->give();
82
hal.scheduler->delay_microseconds(20000);
83
_dev->get_semaphore()->take_blocking();
84
85
// start continuous average mode
86
if (!_send_command(SDP3X_CONT_MEAS_AVG_MODE)) {
87
_dev->get_semaphore()->give();
88
continue;
89
}
90
91
// these delays are needed for reliable operation
92
_dev->get_semaphore()->give();
93
hal.scheduler->delay_microseconds(20000);
94
_dev->get_semaphore()->take_blocking();
95
96
// step 3 - get scale
97
uint8_t val[9];
98
ret = _dev->transfer(nullptr, 0, &val[0], sizeof(val));
99
if (!ret) {
100
_dev->get_semaphore()->give();
101
continue;
102
}
103
104
// Check the CRC
105
if (!_crc(&val[0], 2, val[2]) || !_crc(&val[3], 2, val[5]) || !_crc(&val[6], 2, val[8])) {
106
_dev->get_semaphore()->give();
107
continue;
108
}
109
110
_scale = (((uint16_t)val[6]) << 8) | val[7];
111
112
_dev->get_semaphore()->give();
113
114
found = true;
115
116
#if HAL_GCS_ENABLED
117
char c = 'X';
118
switch (_scale) {
119
case SDP3X_SCALE_PRESSURE_SDP31:
120
c = '1';
121
break;
122
case SDP3X_SCALE_PRESSURE_SDP32:
123
c = '2';
124
break;
125
case SDP3X_SCALE_PRESSURE_SDP33:
126
c = '3';
127
break;
128
}
129
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SDP3%c[%u]: Found bus %u addr 0x%02x scale=%u",
130
get_instance(),
131
c, get_bus(), addresses[i], _scale);
132
#endif
133
}
134
135
if (!found) {
136
return false;
137
}
138
139
/*
140
this sensor uses zero offset and skips cal
141
*/
142
set_use_zero_offset();
143
set_skip_cal();
144
set_offset(0);
145
146
_dev->set_device_type(uint8_t(DevType::SDP3X));
147
set_bus_id(_dev->get_bus_id());
148
149
// drop to 2 retries for runtime
150
_dev->set_retries(2);
151
152
_dev->register_periodic_callback(20000,
153
FUNCTOR_BIND_MEMBER(&AP_Airspeed_SDP3X::_timer, void));
154
return true;
155
}
156
157
// read the values from the sensor. Called at 50Hz
158
void AP_Airspeed_SDP3X::_timer()
159
{
160
// read 6 bytes from the sensor
161
uint8_t val[6];
162
int ret = _dev->transfer(nullptr, 0, &val[0], sizeof(val));
163
uint32_t now = AP_HAL::millis();
164
if (!ret) {
165
if (now - _last_sample_time_ms > 200) {
166
// try and re-connect
167
_send_command(SDP3X_CONT_MEAS_AVG_MODE);
168
}
169
return;
170
}
171
// Check the CRC
172
if (!_crc(&val[0], 2, val[2]) || !_crc(&val[3], 2, val[5])) {
173
return;
174
}
175
176
int16_t P = (((int16_t)val[0]) << 8) | val[1];
177
int16_t temp = (((int16_t)val[3]) << 8) | val[4];
178
179
float diff_press_pa = float(P) / float(_scale);
180
float temperature = float(temp) / SDP3X_SCALE_TEMPERATURE;
181
182
WITH_SEMAPHORE(sem);
183
184
_press_sum += diff_press_pa;
185
_temp_sum += temperature;
186
_press_count++;
187
_temp_count++;
188
_last_sample_time_ms = now;
189
}
190
191
/*
192
correct pressure for barometric height
193
With thanks to:
194
https://github.com/PX4/Firmware/blob/master/Tools/models/sdp3x_pitot_model.py
195
*/
196
float AP_Airspeed_SDP3X::_correct_pressure(float press)
197
{
198
float sign = 1.0f;
199
200
// fix for tube order
201
AP_Airspeed::pitot_tube_order tube_order = get_tube_order();
202
switch (tube_order) {
203
case AP_Airspeed::PITOT_TUBE_ORDER_NEGATIVE:
204
press = -press;
205
sign = -1.0f;
206
break;
207
case AP_Airspeed::PITOT_TUBE_ORDER_POSITIVE:
208
break;
209
case AP_Airspeed::PITOT_TUBE_ORDER_AUTO:
210
default:
211
if (press < 0.0f) {
212
sign = -1.0f;
213
press = -press;
214
}
215
break;
216
}
217
218
if (press <= 0.0f) {
219
return 0.0f;
220
}
221
222
AP_Baro *baro = AP_Baro::get_singleton();
223
224
float baro_pressure;
225
if (baro == nullptr || baro->num_instances() == 0) {
226
// with no baro assume sea level
227
baro_pressure = SSL_AIR_PRESSURE;
228
} else {
229
baro_pressure = baro->get_pressure();
230
}
231
232
float temperature;
233
if (!get_temperature(temperature)) {
234
// assume 25C if no temperature
235
temperature = 25;
236
}
237
238
float rho_air = baro_pressure / (ISA_GAS_CONSTANT * C_TO_KELVIN(temperature));
239
if (!is_positive(rho_air)) {
240
// bad pressure
241
return press;
242
}
243
244
/*
245
the constants in the code below come from a calibrated test of
246
the drotek pitot tube by Sensiron. They are specific to the droktek pitot tube
247
248
At 25m/s, the rough proportions of each pressure correction are:
249
250
- dp_pitot: 5%
251
- press_correction: 14%
252
- press: 81%
253
254
dp_tube has been removed from the Sensiron model as it is
255
insignificant (less than 0.02% over the supported speed ranges)
256
*/
257
258
// flow through sensor
259
float flow_SDP3X = (300.805f - 300.878f / (0.00344205f * (float)powf(press, 0.68698f) + 1.0f)) * 1.29f / rho_air;
260
if (flow_SDP3X < 0.0f) {
261
flow_SDP3X = 0.0f;
262
}
263
264
// differential pressure through pitot tube
265
float dp_pitot = 28557670.0f * (1.0f - 1.0f / (1.0f + (float)powf((flow_SDP3X / 5027611.0f), 1.227924f)));
266
267
// uncorrected pressure
268
float press_uncorrected = (press + dp_pitot) / SSL_AIR_DENSITY;
269
270
// correction for speed at pitot-tube tip due to flow through sensor
271
float dv = 0.0331582f * flow_SDP3X;
272
273
// airspeed ratio
274
float ratio = get_airspeed_ratio();
275
if (!is_positive(ratio)) {
276
// cope with AP_Periph where ratio is 0
277
ratio = 2.0;
278
}
279
280
// calculate equivalent pressure correction. This formula comes
281
// from turning the dv correction above into an equivalent
282
// pressure correction. We need to do this so the airspeed ratio
283
// calibrator can work, as it operates on pressure values
284
float press_correction = sq(sqrtf(press_uncorrected*ratio)+dv)/ratio - press_uncorrected;
285
286
return (press_uncorrected + press_correction) * sign;
287
}
288
289
// return the current differential_pressure in Pascal
290
bool AP_Airspeed_SDP3X::get_differential_pressure(float &pressure)
291
{
292
WITH_SEMAPHORE(sem);
293
294
if (AP_HAL::millis() - _last_sample_time_ms > 100) {
295
return false;
296
}
297
298
if (_press_count > 0) {
299
_press = _press_sum / _press_count;
300
_press_count = 0;
301
_press_sum = 0;
302
}
303
304
pressure = _correct_pressure(_press);
305
return true;
306
}
307
308
// return the current temperature in degrees C, if available
309
bool AP_Airspeed_SDP3X::get_temperature(float &temperature)
310
{
311
WITH_SEMAPHORE(sem);
312
313
if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
314
return false;
315
}
316
317
if (_temp_count > 0) {
318
_temp = _temp_sum / _temp_count;
319
_temp_count = 0;
320
_temp_sum = 0;
321
}
322
323
temperature = _temp;
324
return true;
325
}
326
327
/*
328
check CRC for a set of bytes
329
*/
330
bool AP_Airspeed_SDP3X::_crc(const uint8_t data[], uint8_t size, uint8_t checksum)
331
{
332
uint8_t crc_value = 0xff;
333
334
// calculate 8-bit checksum with polynomial 0x31 (x^8 + x^5 + x^4 + 1)
335
for (uint8_t i = 0; i < size; i++) {
336
crc_value ^= data[i];
337
for (uint8_t bit = 8; bit > 0; --bit) {
338
if (crc_value & 0x80) {
339
crc_value = (crc_value << 1) ^ 0x31;
340
} else {
341
crc_value = (crc_value << 1);
342
}
343
}
344
}
345
// verify checksum
346
return (crc_value == checksum);
347
}
348
349
#endif // AP_AIRSPEED_SDP3X_ENABLED
350
351