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