APM:Libraries
AP_Baro_MS5611.cpp
Go to the documentation of this file.
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 #include <utility>
18 #include <stdio.h>
19 
20 #include <AP_Math/AP_Math.h>
21 
22 extern const AP_HAL::HAL &hal;
23 
24 static const uint8_t CMD_MS56XX_RESET = 0x1E;
25 static const uint8_t CMD_MS56XX_READ_ADC = 0x00;
26 
27 /* PROM start address */
28 static const uint8_t CMD_MS56XX_PROM = 0xA0;
29 
30 /* write to one of these addresses to start pressure conversion */
31 #define ADDR_CMD_CONVERT_D1_OSR256 0x40
32 #define ADDR_CMD_CONVERT_D1_OSR512 0x42
33 #define ADDR_CMD_CONVERT_D1_OSR1024 0x44
34 #define ADDR_CMD_CONVERT_D1_OSR2048 0x46
35 #define ADDR_CMD_CONVERT_D1_OSR4096 0x48
36 
37 /* write to one of these addresses to start temperature conversion */
38 #define ADDR_CMD_CONVERT_D2_OSR256 0x50
39 #define ADDR_CMD_CONVERT_D2_OSR512 0x52
40 #define ADDR_CMD_CONVERT_D2_OSR1024 0x54
41 #define ADDR_CMD_CONVERT_D2_OSR2048 0x56
42 #define ADDR_CMD_CONVERT_D2_OSR4096 0x58
43 
44 /*
45  use an OSR of 1024 to reduce the self-heating effect of the
46  sensor. Information from MS tells us that some individual sensors
47  are quite sensitive to this effect and that reducing the OSR can
48  make a big difference
49  */
52 
53 /*
54  constructor
55  */
57  : AP_Baro_Backend(baro)
58  , _dev(std::move(dev))
59  , _ms56xx_type(ms56xx_type)
60 {
61 }
62 
65  enum MS56XX_TYPE ms56xx_type)
66 {
67  if (!dev) {
68  return nullptr;
69  }
70  AP_Baro_MS56XX *sensor = new AP_Baro_MS56XX(baro, std::move(dev), ms56xx_type);
71  if (!sensor || !sensor->_init()) {
72  delete sensor;
73  return nullptr;
74  }
75  return sensor;
76 }
77 
79 {
80  if (!_dev) {
81  return false;
82  }
83 
85  AP_HAL::panic("PANIC: AP_Baro_MS56XX: failed to take serial semaphore for init");
86  }
87 
88  // high retries for init
89  _dev->set_retries(10);
90 
91  uint16_t prom[8];
92  bool prom_read_ok = false;
93 
94  _dev->transfer(&CMD_MS56XX_RESET, 1, nullptr, 0);
95  hal.scheduler->delay(4);
96 
97  const char *name = "MS5611";
98  switch (_ms56xx_type) {
99  case BARO_MS5607:
100  name = "MS5607";
101  FALLTHROUGH;
102  case BARO_MS5611:
103  prom_read_ok = _read_prom_5611(prom);
104  break;
105  case BARO_MS5837:
106  name = "MS5837";
107  prom_read_ok = _read_prom_5637(prom);
108  break;
109  case BARO_MS5637:
110  name = "MS5637";
111  prom_read_ok = _read_prom_5637(prom);
112  break;
113  }
114 
115  if (!prom_read_ok) {
116  _dev->get_semaphore()->give();
117  return false;
118  }
119 
120  printf("%s found on bus %u address 0x%02x\n", name, _dev->bus_num(), _dev->get_bus_address());
121 
122  // Save factory calibration coefficients
123  _cal_reg.c1 = prom[1];
124  _cal_reg.c2 = prom[2];
125  _cal_reg.c3 = prom[3];
126  _cal_reg.c4 = prom[4];
127  _cal_reg.c5 = prom[5];
128  _cal_reg.c6 = prom[6];
129 
130  // Send a command to read temperature first
131  _dev->transfer(&ADDR_CMD_CONVERT_TEMPERATURE, 1, nullptr, 0);
132  _state = 0;
133 
134  memset(&_accum, 0, sizeof(_accum));
135 
137 
138  if (_ms56xx_type == BARO_MS5837) {
140  }
141 
142  // lower retries for run
143  _dev->set_retries(3);
144 
145  _dev->get_semaphore()->give();
146 
147  /* Request 100Hz update */
150  return true;
151 }
152 
156 static uint16_t crc4(uint16_t *data)
157 {
158  uint16_t n_rem = 0;
159  uint8_t n_bit;
160 
161  for (uint8_t cnt = 0; cnt < 16; cnt++) {
162  /* uneven bytes */
163  if (cnt & 1) {
164  n_rem ^= (uint8_t)((data[cnt >> 1]) & 0x00FF);
165  } else {
166  n_rem ^= (uint8_t)(data[cnt >> 1] >> 8);
167  }
168 
169  for (n_bit = 8; n_bit > 0; n_bit--) {
170  if (n_rem & 0x8000) {
171  n_rem = (n_rem << 1) ^ 0x3000;
172  } else {
173  n_rem = (n_rem << 1);
174  }
175  }
176  }
177 
178  return (n_rem >> 12) & 0xF;
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 
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 == 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 == 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 */
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
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) {
295  // a failed read can mean the next returned value will be
296  // corrupt, we must discard it
297  _discard_next = true;
298  return;
299  }
300 
301  if (_discard_next) {
302  _discard_next = false;
303  _state = next_state;
304  return;
305  }
306 
308  if (_state == 0) {
309  _update_and_wrap_accumulator(&_accum.s_D2, adc_val,
310  &_accum.d2_count, 32);
311  } else {
312  if (pressure_ok(adc_val)) {
313  _update_and_wrap_accumulator(&_accum.s_D1, adc_val,
314  &_accum.d1_count, 128);
315  }
316  }
317  _sem->give();
318  _state = next_state;
319  }
320 }
321 
322 void AP_Baro_MS56XX::_update_and_wrap_accumulator(uint32_t *accum, uint32_t val,
323  uint8_t *count, uint8_t max_count)
324 {
325  *accum += val;
326  *count += 1;
327  if (*count == max_count) {
328  *count = max_count / 2;
329  *accum = *accum / 2;
330  }
331 }
332 
334 {
335  uint32_t sD1, sD2;
336  uint8_t d1count, d2count;
337 
339  return;
340  }
341 
342  if (_accum.d1_count == 0) {
343  _sem->give();
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  _sem->give();
354 
355  if (d1count != 0) {
356  _D1 = ((float)sD1) / d1count;
357  }
358  if (d2count != 0) {
359  _D2 = ((float)sD2) / d2count;
360  }
361 
362  switch (_ms56xx_type) {
363  case BARO_MS5607:
364  _calculate_5607();
365  break;
366  case BARO_MS5611:
367  _calculate_5611();
368  break;
369  case BARO_MS5637:
370  _calculate_5637();
371  break;
372  case BARO_MS5837:
373  _calculate_5837();
374  }
375 }
376 
377 // Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
379 {
380  float dT;
381  float TEMP;
382  float OFF;
383  float SENS;
384 
385  // Formulas from manufacturer datasheet
386  // sub -15c temperature compensation is not included
387 
388  // we do the calculations using floating point allows us to take advantage
389  // of the averaging of D1 and D1 over multiple samples, giving us more
390  // precision
391  dT = _D2-(((uint32_t)_cal_reg.c5)<<8);
392  TEMP = (dT * _cal_reg.c6)/8388608;
393  OFF = _cal_reg.c2 * 65536.0f + (_cal_reg.c4 * dT) / 128;
394  SENS = _cal_reg.c1 * 32768.0f + (_cal_reg.c3 * dT) / 256;
395 
396  if (TEMP < 0) {
397  // second order temperature compensation when under 20 degrees C
398  float T2 = (dT*dT) / 0x80000000;
399  float Aux = TEMP*TEMP;
400  float OFF2 = 2.5f*Aux;
401  float SENS2 = 1.25f*Aux;
402  TEMP = TEMP - T2;
403  OFF = OFF - OFF2;
404  SENS = SENS - SENS2;
405  }
406 
407  float pressure = (_D1*SENS/2097152 - OFF)/32768;
408  float temperature = (TEMP + 2000) * 0.01f;
409  _copy_to_frontend(_instance, pressure, temperature);
410 }
411 
412 // Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
414 {
415  float dT;
416  float TEMP;
417  float OFF;
418  float SENS;
419 
420  // Formulas from manufacturer datasheet
421  // sub -15c temperature compensation is not included
422 
423  // we do the calculations using floating point allows us to take advantage
424  // of the averaging of D1 and D1 over multiple samples, giving us more
425  // precision
426  dT = _D2-(((uint32_t)_cal_reg.c5)<<8);
427  TEMP = (dT * _cal_reg.c6)/8388608;
428  OFF = _cal_reg.c2 * 131072.0f + (_cal_reg.c4 * dT) / 64;
429  SENS = _cal_reg.c1 * 65536.0f + (_cal_reg.c3 * dT) / 128;
430 
431  if (TEMP < 0) {
432  // second order temperature compensation when under 20 degrees C
433  float T2 = (dT*dT) / 0x80000000;
434  float Aux = TEMP*TEMP;
435  float OFF2 = 61.0f*Aux/16.0f;
436  float SENS2 = 2.0f*Aux;
437  TEMP = TEMP - T2;
438  OFF = OFF - OFF2;
439  SENS = SENS - SENS2;
440  }
441 
442  float pressure = (_D1*SENS/2097152 - OFF)/32768;
443  float temperature = (TEMP + 2000) * 0.01f;
444  _copy_to_frontend(_instance, pressure, temperature);
445 }
446 
447 // Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
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  // Formulas from manufacturer datasheet
456  // sub -15c temperature compensation is not included
457 
458  dT = raw_temperature - (((uint32_t)_cal_reg.c5) << 8);
459  TEMP = 2000 + ((int64_t)dT * (int64_t)_cal_reg.c6) / 8388608;
460  OFF = (int64_t)_cal_reg.c2 * (int64_t)131072 + ((int64_t)_cal_reg.c4 * (int64_t)dT) / (int64_t)64;
461  SENS = (int64_t)_cal_reg.c1 * (int64_t)65536 + ((int64_t)_cal_reg.c3 * (int64_t)dT) / (int64_t)128;
462 
463  if (TEMP < 2000) {
464  // second order temperature compensation when under 20 degrees C
465  int32_t T2 = ((int64_t)3 * ((int64_t)dT * (int64_t)dT) / (int64_t)8589934592);
466  int64_t aux = (TEMP - 2000) * (TEMP - 2000);
467  int64_t OFF2 = 61 * aux / 16;
468  int64_t SENS2 = 29 * aux / 16;
469 
470  TEMP = TEMP - T2;
471  OFF = OFF - OFF2;
472  SENS = SENS - SENS2;
473  }
474 
475  int32_t pressure = ((int64_t)raw_pressure * SENS / (int64_t)2097152 - OFF) / (int64_t)32768;
476  float temperature = TEMP * 0.01f;
477  _copy_to_frontend(_instance, (float)pressure, temperature);
478 }
479 
480 // Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
482 {
483  int32_t dT, TEMP;
484  int64_t OFF, SENS;
485  int32_t raw_pressure = _D1;
486  int32_t raw_temperature = _D2;
487 
488  // Formulas from manufacturer datasheet
489  // sub -15c temperature compensation is not included
490 
491  dT = raw_temperature - (((uint32_t)_cal_reg.c5) << 8);
492  TEMP = 2000 + ((int64_t)dT * (int64_t)_cal_reg.c6) / 8388608;
493  OFF = (int64_t)_cal_reg.c2 * (int64_t)65536 + ((int64_t)_cal_reg.c4 * (int64_t)dT) / (int64_t)128;
494  SENS = (int64_t)_cal_reg.c1 * (int64_t)32768 + ((int64_t)_cal_reg.c3 * (int64_t)dT) / (int64_t)256;
495 
496  if (TEMP < 2000) {
497  // second order temperature compensation when under 20 degrees C
498  int32_t T2 = ((int64_t)3 * ((int64_t)dT * (int64_t)dT) / (int64_t)8589934592);
499  int64_t aux = (TEMP - 2000) * (TEMP - 2000);
500  int64_t OFF2 = 3 * aux / 2;
501  int64_t SENS2 = 5 * aux / 8;
502 
503  TEMP = TEMP - T2;
504  OFF = OFF - OFF2;
505  SENS = SENS - SENS2;
506  }
507 
508  int32_t pressure = ((int64_t)raw_pressure * SENS / (int64_t)2097152 - OFF) / (int64_t)8192;
509  pressure = pressure * 10; // MS5837 only reports to 0.1 mbar
510  float temperature = TEMP * 0.01f;
511 
512  _copy_to_frontend(_instance, (float)pressure, temperature);
513 }
int printf(const char *fmt,...)
Definition: stdio.c:113
static void _update_and_wrap_accumulator(uint32_t *accum, uint32_t val, uint8_t *count, uint8_t max_count)
#define AP_USEC_PER_MSEC
Definition: definitions.h:93
static const uint8_t ADDR_CMD_CONVERT_PRESSURE
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
#define FALLTHROUGH
Definition: AP_Common.h:50
void _copy_to_frontend(uint8_t instance, float pressure, float temperature)
uint8_t register_sensor(void)
Definition: AP_Baro.cpp:705
static uint16_t crc4(uint16_t *data)
AP_HAL::Semaphore * _sem
virtual AP_HAL::Semaphore * get_semaphore()=0
virtual void set_retries(uint8_t retries)
Definition: Device.h:260
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum MS56XX_TYPE ms56xx_type=BARO_MS5611)
uint8_t get_bus_address(void) const
Definition: Device.h:65
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
const char * name
Definition: BusTest.cpp:11
uint8_t bus_num(void) const
Definition: Device.h:55
struct AP_Baro_MS56XX::@11 _cal_reg
static const uint8_t ADDR_CMD_CONVERT_TEMPERATURE
float temperature
Definition: Airspeed.cpp:32
virtual void delay(uint16_t ms)=0
uint16_t _read_prom_word(uint8_t word)
static const uint8_t CMD_MS56XX_PROM
AP_Baro & _frontend
struct AP_Baro_MS56XX::@10 _accum
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
#define f(i)
static AP_Baro baro
Definition: ModuleTest.cpp:18
bool pressure_ok(float press)
static const uint8_t CMD_MS56XX_RESET
AP_Baro_MS56XX(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum MS56XX_TYPE ms56xx_type)
static const uint8_t CMD_MS56XX_READ_ADC
bool _read_prom_5611(uint16_t prom[8])
virtual bool give()=0
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len)=0
void set_type(uint8_t instance, baro_type_t type)
Definition: AP_Baro.h:136
AP_HAL::OwnPtr< AP_HAL::Device > _dev
#define ADDR_CMD_CONVERT_D1_OSR1024
enum MS56XX_TYPE _ms56xx_type
uint32_t _read_adc()
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
bool _read_prom_5637(uint16_t prom[8])
#define ADDR_CMD_CONVERT_D2_OSR1024
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114