Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Baro/AP_Baro_MS5611.cpp
9699 views
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
#include "AP_Baro_MS5611.h"
16
17
#if AP_BARO_MS56XX_ENABLED
18
19
#include <stdio.h>
20
21
#include <AP_Math/AP_Math.h>
22
#include <AP_Math/crc.h>
23
#include <AP_BoardConfig/AP_BoardConfig.h>
24
25
extern const AP_HAL::HAL &hal;
26
27
static const uint8_t CMD_MS56XX_RESET = 0x1E;
28
static const uint8_t CMD_MS56XX_READ_ADC = 0x00;
29
30
/* PROM start address */
31
static const uint8_t CMD_MS56XX_PROM = 0xA0;
32
33
/* write to one of these addresses to start pressure conversion */
34
#define ADDR_CMD_CONVERT_D1_OSR256 0x40
35
#define ADDR_CMD_CONVERT_D1_OSR512 0x42
36
#define ADDR_CMD_CONVERT_D1_OSR1024 0x44
37
#define ADDR_CMD_CONVERT_D1_OSR2048 0x46
38
#define ADDR_CMD_CONVERT_D1_OSR4096 0x48
39
40
/* write to one of these addresses to start temperature conversion */
41
#define ADDR_CMD_CONVERT_D2_OSR256 0x50
42
#define ADDR_CMD_CONVERT_D2_OSR512 0x52
43
#define ADDR_CMD_CONVERT_D2_OSR1024 0x54
44
#define ADDR_CMD_CONVERT_D2_OSR2048 0x56
45
#define ADDR_CMD_CONVERT_D2_OSR4096 0x58
46
47
/*
48
use an OSR of 1024 to reduce the self-heating effect of the
49
sensor. Information from MS tells us that some individual sensors
50
are quite sensitive to this effect and that reducing the OSR can
51
make a big difference
52
*/
53
static const uint8_t ADDR_CMD_CONVERT_PRESSURE = ADDR_CMD_CONVERT_D1_OSR1024;
54
static const uint8_t ADDR_CMD_CONVERT_TEMPERATURE = ADDR_CMD_CONVERT_D2_OSR1024;
55
56
/*
57
constructor
58
*/
59
AP_Baro_MS56XX::AP_Baro_MS56XX(AP_Baro &baro, AP_HAL::Device &dev)
60
: AP_Baro_Backend(baro)
61
, _dev(&dev)
62
{
63
}
64
65
// convenience methods for derivative classes to call. Will free
66
// sensor if it can't init it.
67
AP_Baro_Backend *AP_Baro_MS56XX::_probe(AP_Baro &baro, AP_Baro_MS56XX *sensor)
68
{
69
if (!sensor || !sensor->_init()) {
70
delete sensor;
71
return nullptr;
72
}
73
return sensor;
74
}
75
76
#if AP_BARO_MS5611_ENABLED
77
AP_Baro_Backend *AP_Baro_MS5611::probe(AP_Baro &baro, AP_HAL::Device &dev)
78
{
79
#if AP_BARO_MS5607_ENABLED
80
/*
81
cope with vendors substituting a MS5607 for a MS5611 on Pixhawk1 'clone' boards
82
*/
83
if (AP::baro().option_enabled(AP_Baro::Options::TreatMS5611AsMS5607)) {
84
return _probe(baro, NEW_NOTHROW AP_Baro_MS5607(baro, dev));
85
}
86
#endif // AP_BARO_MS5607_ENABLED
87
88
return _probe(baro, NEW_NOTHROW AP_Baro_MS5611(baro, dev));
89
}
90
#endif // AP_BARO_MS5611_ENABLED
91
92
#if AP_BARO_MS5607_ENABLED
93
AP_Baro_Backend *AP_Baro_MS5607::probe(AP_Baro &baro, AP_HAL::Device &dev)
94
{
95
return _probe(baro, NEW_NOTHROW AP_Baro_MS5607(baro, dev));
96
}
97
#endif // AP_BARO_MS5607_ENABLED
98
99
#if AP_BARO_MS5637_ENABLED
100
AP_Baro_Backend *AP_Baro_MS5637::probe(AP_Baro &baro, AP_HAL::Device &dev)
101
{
102
return _probe(baro, NEW_NOTHROW AP_Baro_MS5637(baro, dev));
103
}
104
#endif // AP_BARO_MS5637_ENABLED
105
106
#if AP_BARO_MS5837_ENABLED
107
AP_Baro_Backend *AP_Baro_MS5837::probe(AP_Baro &baro, AP_HAL::Device &dev)
108
{
109
return _probe(baro, NEW_NOTHROW AP_Baro_MS5837(baro, dev));
110
}
111
112
bool AP_Baro_MS5837::_init()
113
{
114
if (!AP_Baro_MS56XX::_init()) {
115
return false;
116
}
117
_frontend.set_type(_instance, AP_Baro::BARO_TYPE_WATER);
118
// Use pressure sensitivity as a proxy for range determination
119
// High sensitivity for the same number size implies the lower-range sensor variant
120
// Threshold determined from datasheet example values and some sample sensors
121
uint16_t pressure_sensitivity = _cal_reg.c1;
122
if (pressure_sensitivity > MS5837_30BA_02BA_SELECTION_THRESHOLD) {
123
_subtype = DEVTYPE_BARO_MS5837_02BA;
124
} else {
125
_subtype = DEVTYPE_BARO_MS5837_30BA;
126
}
127
return true;
128
}
129
#endif // AP_BARO_MS5837_ENABLED
130
131
bool AP_Baro_MS56XX::_init()
132
{
133
if (!_dev) {
134
return false;
135
}
136
137
_dev->get_semaphore()->take_blocking();
138
139
// high retries for init
140
_dev->set_retries(10);
141
142
uint16_t prom[8];
143
144
_dev->transfer(&CMD_MS56XX_RESET, 1, nullptr, 0);
145
hal.scheduler->delay(4);
146
147
if (!_read_prom(prom)) {
148
_dev->get_semaphore()->give();
149
return false;
150
}
151
152
printf("%s found on bus %u address 0x%02x\n", name(), _dev->bus_num(), _dev->get_bus_address());
153
154
// Save factory calibration coefficients
155
_cal_reg.c1 = prom[1];
156
_cal_reg.c2 = prom[2];
157
_cal_reg.c3 = prom[3];
158
_cal_reg.c4 = prom[4];
159
_cal_reg.c5 = prom[5];
160
_cal_reg.c6 = prom[6];
161
162
// Send a command to read temperature first
163
_dev->transfer(&ADDR_CMD_CONVERT_TEMPERATURE, 1, nullptr, 0);
164
_state = 0;
165
166
memset(&_accum, 0, sizeof(_accum));
167
168
_instance = _frontend.register_sensor();
169
170
_dev->set_device_type(devtype());
171
set_bus_id(_instance, _dev->get_bus_id());
172
173
// lower retries for run
174
_dev->set_retries(3);
175
176
_dev->get_semaphore()->give();
177
178
/* Request 100Hz update */
179
_dev->register_periodic_callback(10 * AP_USEC_PER_MSEC,
180
FUNCTOR_BIND_MEMBER(&AP_Baro_MS56XX::_timer, void));
181
return true;
182
}
183
184
uint16_t AP_Baro_MS56XX::_read_prom_word(uint8_t word)
185
{
186
const uint8_t reg = CMD_MS56XX_PROM + (word << 1);
187
uint8_t val[2];
188
if (!_dev->transfer(&reg, 1, val, sizeof(val))) {
189
return 0;
190
}
191
return (val[0] << 8) | val[1];
192
}
193
194
uint32_t AP_Baro_MS56XX::_read_adc()
195
{
196
uint8_t val[3];
197
if (!_dev->transfer(&CMD_MS56XX_READ_ADC, 1, val, sizeof(val))) {
198
return 0;
199
}
200
return (val[0] << 16) | (val[1] << 8) | val[2];
201
}
202
203
bool AP_Baro_MS56XX::_read_prom_5611(uint16_t prom[8])
204
{
205
/*
206
* MS5611-01BA datasheet, CYCLIC REDUNDANCY CHECK (CRC): "MS5611-01BA
207
* contains a PROM memory with 128-Bit. A 4-bit CRC has been implemented
208
* to check the data validity in memory."
209
*
210
* CRC field must me removed for CRC-4 calculation.
211
*/
212
bool all_zero = true;
213
for (uint8_t i = 0; i < 8; i++) {
214
prom[i] = _read_prom_word(i);
215
if (prom[i] != 0) {
216
all_zero = false;
217
}
218
}
219
220
if (all_zero) {
221
return false;
222
}
223
224
/* save the read crc */
225
const uint16_t crc_read = prom[7] & 0xf;
226
227
/* remove CRC byte */
228
prom[7] &= 0xff00;
229
230
return crc_read == crc_crc4(prom);
231
}
232
233
bool AP_Baro_MS56XX::_read_prom_5637(uint16_t prom[8])
234
{
235
/*
236
* MS5637-02BA03 datasheet, CYCLIC REDUNDANCY CHECK (CRC): "MS5637
237
* contains a PROM memory with 112-Bit. A 4-bit CRC has been implemented
238
* to check the data validity in memory."
239
*
240
* 8th PROM word must be zeroed and CRC field removed for CRC-4
241
* calculation.
242
*/
243
bool all_zero = true;
244
for (uint8_t i = 0; i < 7; i++) {
245
prom[i] = _read_prom_word(i);
246
if (prom[i] != 0) {
247
all_zero = false;
248
}
249
}
250
251
if (all_zero) {
252
return false;
253
}
254
255
prom[7] = 0;
256
257
/* save the read crc */
258
const uint16_t crc_read = (prom[0] & 0xf000) >> 12;
259
260
/* remove CRC byte */
261
prom[0] &= ~0xf000;
262
263
return crc_read == crc_crc4(prom);
264
}
265
266
/*
267
* Read the sensor with a state machine
268
* We read one time temperature (state=0) and then 4 times pressure (states 1-4)
269
*
270
* Temperature is used to calculate the compensated pressure and doesn't vary
271
* as fast as pressure. Hence we reuse the same temperature for 4 samples of
272
* pressure.
273
*/
274
void AP_Baro_MS56XX::_timer(void)
275
{
276
uint8_t next_cmd;
277
uint8_t next_state;
278
uint32_t adc_val = _read_adc();
279
280
/*
281
* If read fails, re-initiate a read command for current state or we are
282
* stuck
283
*/
284
if (adc_val == 0) {
285
next_state = _state;
286
} else {
287
next_state = (_state + 1) % 5;
288
}
289
290
next_cmd = next_state == 0 ? ADDR_CMD_CONVERT_TEMPERATURE
291
: ADDR_CMD_CONVERT_PRESSURE;
292
if (!_dev->transfer(&next_cmd, 1, nullptr, 0)) {
293
return;
294
}
295
296
/* if we had a failed read we are all done */
297
if (adc_val == 0 || adc_val == 0xFFFFFF) {
298
// a failed read can mean the next returned value will be
299
// corrupt, we must discard it. This copes with MISO being
300
// pulled either high or low
301
_discard_next = true;
302
return;
303
}
304
305
if (_discard_next) {
306
_discard_next = false;
307
_state = next_state;
308
return;
309
}
310
311
WITH_SEMAPHORE(_sem);
312
313
if (_state == 0) {
314
_update_and_wrap_accumulator(&_accum.s_D2, adc_val,
315
&_accum.d2_count, 32);
316
} else if (pressure_ok(adc_val)) {
317
_update_and_wrap_accumulator(&_accum.s_D1, adc_val,
318
&_accum.d1_count, 128);
319
}
320
321
_state = next_state;
322
}
323
324
void AP_Baro_MS56XX::_update_and_wrap_accumulator(uint32_t *accum, uint32_t val,
325
uint8_t *count, uint8_t max_count)
326
{
327
*accum += val;
328
*count += 1;
329
if (*count == max_count) {
330
*count = max_count / 2;
331
*accum = *accum / 2;
332
}
333
}
334
335
void AP_Baro_MS56XX::update()
336
{
337
uint32_t sD1, sD2;
338
uint8_t d1count, d2count;
339
340
{
341
WITH_SEMAPHORE(_sem);
342
343
if (_accum.d1_count == 0) {
344
return;
345
}
346
347
sD1 = _accum.s_D1;
348
sD2 = _accum.s_D2;
349
d1count = _accum.d1_count;
350
d2count = _accum.d2_count;
351
memset(&_accum, 0, sizeof(_accum));
352
}
353
354
if (d1count != 0) {
355
_D1 = ((float)sD1) / d1count;
356
}
357
if (d2count != 0) {
358
_D2 = ((float)sD2) / d2count;
359
}
360
361
_calculate();
362
}
363
364
#if AP_BARO_MS5611_ENABLED
365
// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
366
void AP_Baro_MS5611::_calculate()
367
{
368
float dT;
369
float TEMP;
370
float OFF;
371
float SENS;
372
373
// we do the calculations using floating point allows us to take advantage
374
// of the averaging of D1 and D1 over multiple samples, giving us more
375
// precision
376
dT = _D2-(((uint32_t)_cal_reg.c5)<<8);
377
TEMP = (dT * _cal_reg.c6)/8388608;
378
OFF = _cal_reg.c2 * 65536.0f + (_cal_reg.c4 * dT) / 128;
379
SENS = _cal_reg.c1 * 32768.0f + (_cal_reg.c3 * dT) / 256;
380
381
TEMP += 2000;
382
383
if (TEMP < 2000) {
384
// second order temperature compensation when under 20 degrees C
385
float T2 = (dT*dT) / 0x80000000;
386
float Aux = sq(TEMP-2000.0);
387
float OFF2 = 2.5f*Aux;
388
float SENS2 = 1.25f*Aux;
389
if (TEMP < -1500) {
390
// extra compensation for temperatures below -15C
391
OFF2 += 7 * sq(TEMP+1500);
392
SENS2 += sq(TEMP+1500) * 11.0*0.5;
393
}
394
TEMP = TEMP - T2;
395
OFF = OFF - OFF2;
396
SENS = SENS - SENS2;
397
}
398
399
400
float pressure = (_D1*SENS/2097152 - OFF)/32768;
401
float temperature = TEMP * 0.01f;
402
_copy_to_frontend(_instance, pressure, temperature);
403
}
404
#endif // AP_BARO_MS5611_ENABLED
405
406
#if AP_BARO_MS5607_ENABLED
407
// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
408
void AP_Baro_MS5607::_calculate()
409
{
410
float dT;
411
float TEMP;
412
float OFF;
413
float SENS;
414
415
// we do the calculations using floating point allows us to take advantage
416
// of the averaging of D1 and D1 over multiple samples, giving us more
417
// precision
418
dT = _D2-(((uint32_t)_cal_reg.c5)<<8);
419
TEMP = (dT * _cal_reg.c6)/8388608;
420
OFF = _cal_reg.c2 * 131072.0f + (_cal_reg.c4 * dT) / 64;
421
SENS = _cal_reg.c1 * 65536.0f + (_cal_reg.c3 * dT) / 128;
422
423
TEMP += 2000;
424
425
if (TEMP < 2000) {
426
// second order temperature compensation when under 20 degrees C
427
float T2 = (dT*dT) / 0x80000000;
428
float Aux = sq(TEMP-2000);
429
float OFF2 = 61.0f*Aux/16.0f;
430
float SENS2 = 2.0f*Aux;
431
if (TEMP < -1500) {
432
OFF2 += 15 * sq(TEMP+1500);
433
SENS2 += 8 * sq(TEMP+1500);
434
}
435
TEMP = TEMP - T2;
436
OFF = OFF - OFF2;
437
SENS = SENS - SENS2;
438
}
439
440
float pressure = (_D1*SENS/2097152 - OFF)/32768;
441
float temperature = TEMP * 0.01f;
442
_copy_to_frontend(_instance, pressure, temperature);
443
}
444
#endif // AP_BARO_MS5607_ENABLED
445
446
#if AP_BARO_MS5637_ENABLED
447
// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
448
void AP_Baro_MS5637::_calculate()
449
{
450
int32_t dT, TEMP;
451
int64_t OFF, SENS;
452
int32_t raw_pressure = _D1;
453
int32_t raw_temperature = _D2;
454
455
dT = raw_temperature - (((uint32_t)_cal_reg.c5) << 8);
456
TEMP = 2000 + ((int64_t)dT * (int64_t)_cal_reg.c6) / 8388608;
457
OFF = (int64_t)_cal_reg.c2 * (int64_t)131072 + ((int64_t)_cal_reg.c4 * (int64_t)dT) / (int64_t)64;
458
SENS = (int64_t)_cal_reg.c1 * (int64_t)65536 + ((int64_t)_cal_reg.c3 * (int64_t)dT) / (int64_t)128;
459
460
if (TEMP < 2000) {
461
// second order temperature compensation when under 20 degrees C
462
int32_t T2 = ((int64_t)3 * ((int64_t)dT * (int64_t)dT) / (int64_t)8589934592);
463
int64_t aux = (TEMP - 2000) * (TEMP - 2000);
464
int64_t OFF2 = 61 * aux / 16;
465
int64_t SENS2 = 29 * aux / 16;
466
467
if (TEMP < -1500) {
468
OFF2 += 17 * sq(TEMP+1500);
469
SENS2 += 9 * sq(TEMP+1500);
470
}
471
472
TEMP = TEMP - T2;
473
OFF = OFF - OFF2;
474
SENS = SENS - SENS2;
475
}
476
477
int32_t pressure = ((int64_t)raw_pressure * SENS / (int64_t)2097152 - OFF) / (int64_t)32768;
478
float temperature = TEMP * 0.01f;
479
_copy_to_frontend(_instance, (float)pressure, temperature);
480
}
481
#endif // AP_BARO_MS5637_ENABLED
482
483
#if AP_BARO_MS5837_ENABLED
484
// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
485
void AP_Baro_MS5837::_calculate()
486
{
487
if (_subtype == DEVTYPE_BARO_MS5837_02BA) {
488
_calculate_5837_02ba();
489
} else {
490
_calculate_5837_30ba();
491
}
492
}
493
494
// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
495
void AP_Baro_MS5837::_calculate_5837_30ba()
496
{
497
int32_t dT, TEMP, T2;
498
int64_t OFF, OFF2, SENS, SENS2;
499
int32_t raw_pressure = _D1;
500
int32_t raw_temperature = _D2;
501
502
dT = raw_temperature - ((uint32_t)_cal_reg.c5 << 8);
503
TEMP = 2000 + ((int64_t)dT * (int64_t)_cal_reg.c6) / 8388608;
504
OFF = (int64_t)_cal_reg.c2 * (int64_t)65536 + ((int64_t)_cal_reg.c4 * (int64_t)dT) / (int64_t)128;
505
SENS = (int64_t)_cal_reg.c1 * (int64_t)32768 + ((int64_t)_cal_reg.c3 * (int64_t)dT) / (int64_t)256;
506
507
int64_t aux = sq(TEMP - 2000);
508
if (TEMP < 2000) {
509
// second order "low temperature" compensation when under 20 degrees C
510
T2 = (int64_t)3 * sq((int64_t)dT) / (int64_t)8589934592;
511
OFF2 = 3 * aux / 2;
512
SENS2 = 5 * aux / 8;
513
514
if (TEMP < -1500) {
515
// "very low temperature" compensation, when under -15 degrees C
516
OFF2 += 7 * sq(TEMP+1500);
517
SENS2 += 4 * sq(TEMP+1500);
518
}
519
} else {
520
// "high temperature" compensation, when at or over 20 degrees C
521
T2 = (int64_t)2 * sq((int64_t)dT) / (int64_t)137438953472;
522
OFF2 = aux / 16;
523
SENS2 = 0;
524
}
525
TEMP = TEMP - T2;
526
OFF = OFF - OFF2;
527
SENS = SENS - SENS2;
528
529
int32_t pressure = ((int64_t)raw_pressure * SENS / (int64_t)2097152 - OFF) / (int64_t)8192;
530
pressure = pressure * 10; // MS5837 only reports to 0.1 mbar
531
float temperature = TEMP * 0.01f;
532
533
_copy_to_frontend(_instance, (float)pressure, temperature);
534
}
535
// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
536
void AP_Baro_MS5837::_calculate_5837_02ba() {
537
int32_t dT = _D2 - ((int32_t)_cal_reg.c5 << 8);
538
int32_t TEMP = 2000 + ((dT * _cal_reg.c6) >> 23);
539
540
int64_t OFF = ((int64_t)_cal_reg.c2 << 17) + (((int64_t)_cal_reg.c4 * dT) >> 6);
541
int64_t SENS = ((int64_t)_cal_reg.c1 << 16) + (((int64_t)_cal_reg.c3 * dT) >> 7);
542
543
if (TEMP < 2000) {
544
// Second-order compensation
545
int32_t T2 = ((int64_t)11 * (int64_t)sq((int64_t)dT)) >> 35;
546
int64_t aux = sq(TEMP - 2000);
547
int64_t OFF2 = 31 * aux >> 3;
548
int64_t SENS2 = 63 * aux >> 5;
549
550
TEMP -= T2;
551
OFF -= OFF2;
552
SENS -= SENS2;
553
}
554
555
// Cast _D1 to int64_t before performing multiplication and shift
556
int64_t pressure = ((((int64_t)_D1 * SENS) >> 21) - OFF) >> 15;
557
558
// Update frontend with calculated values
559
_copy_to_frontend(_instance, (float)pressure, (float)TEMP / 100);
560
}
561
562
AP_Baro_Backend::DevTypes AP_Baro_MS5837::devtype() const {
563
return _subtype;
564
}
565
566
#endif // AP_BARO_MS5837_ENABLED
567
568
#endif // AP_BARO_MS56XX_ENABLED
569
570