AP_Baro_MS5611.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #include "AP_Baro_MS5611.h"
  14. #include <utility>
  15. #include <stdio.h>
  16. #include <AP_Math/AP_Math.h>
  17. #include <AP_Math/crc.h>
  18. extern const AP_HAL::HAL &hal;
  19. static const uint8_t CMD_MS56XX_RESET = 0x1E;
  20. static const uint8_t CMD_MS56XX_READ_ADC = 0x00;
  21. /* PROM start address */
  22. static const uint8_t CMD_MS56XX_PROM = 0xA0;
  23. /* write to one of these addresses to start pressure conversion */
  24. #define ADDR_CMD_CONVERT_D1_OSR256 0x40
  25. #define ADDR_CMD_CONVERT_D1_OSR512 0x42
  26. #define ADDR_CMD_CONVERT_D1_OSR1024 0x44
  27. #define ADDR_CMD_CONVERT_D1_OSR2048 0x46
  28. #define ADDR_CMD_CONVERT_D1_OSR4096 0x48
  29. /* write to one of these addresses to start temperature conversion */
  30. #define ADDR_CMD_CONVERT_D2_OSR256 0x50
  31. #define ADDR_CMD_CONVERT_D2_OSR512 0x52
  32. #define ADDR_CMD_CONVERT_D2_OSR1024 0x54
  33. #define ADDR_CMD_CONVERT_D2_OSR2048 0x56
  34. #define ADDR_CMD_CONVERT_D2_OSR4096 0x58
  35. /*
  36. use an OSR of 1024 to reduce the self-heating effect of the
  37. sensor. Information from MS tells us that some individual sensors
  38. are quite sensitive to this effect and that reducing the OSR can
  39. make a big difference
  40. */
  41. static const uint8_t ADDR_CMD_CONVERT_PRESSURE = ADDR_CMD_CONVERT_D1_OSR1024;
  42. static const uint8_t ADDR_CMD_CONVERT_TEMPERATURE = ADDR_CMD_CONVERT_D2_OSR1024;
  43. /*
  44. constructor
  45. */
  46. AP_Baro_MS56XX::AP_Baro_MS56XX(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, enum MS56XX_TYPE ms56xx_type)
  47. : AP_Baro_Backend(baro)
  48. , _dev(std::move(dev))
  49. , _ms56xx_type(ms56xx_type)
  50. {
  51. }
  52. AP_Baro_Backend *AP_Baro_MS56XX::probe(AP_Baro &baro,
  53. AP_HAL::OwnPtr<AP_HAL::Device> dev,
  54. enum MS56XX_TYPE ms56xx_type)
  55. {
  56. if (!dev) {
  57. return nullptr;
  58. }
  59. AP_Baro_MS56XX *sensor = new AP_Baro_MS56XX(baro, std::move(dev), ms56xx_type);
  60. if (!sensor || !sensor->_init()) {
  61. delete sensor;
  62. return nullptr;
  63. }
  64. return sensor;
  65. }
  66. bool AP_Baro_MS56XX::_init()
  67. {
  68. if (!_dev) {
  69. return false;
  70. }
  71. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  72. AP_HAL::panic("PANIC: AP_Baro_MS56XX: failed to take serial semaphore for init");
  73. }
  74. // high retries for init
  75. _dev->set_retries(10);
  76. uint16_t prom[8];
  77. bool prom_read_ok = false;
  78. _dev->transfer(&CMD_MS56XX_RESET, 1, nullptr, 0);
  79. hal.scheduler->delay(4);
  80. const char *name = "MS5611";
  81. switch (_ms56xx_type) {
  82. case BARO_MS5607:
  83. name = "MS5607";
  84. FALLTHROUGH;
  85. case BARO_MS5611:
  86. prom_read_ok = _read_prom_5611(prom);
  87. break;
  88. case BARO_MS5837:
  89. name = "MS5837";
  90. prom_read_ok = _read_prom_5637(prom);
  91. break;
  92. case BARO_MS5637:
  93. name = "MS5637";
  94. prom_read_ok = _read_prom_5637(prom);
  95. break;
  96. }
  97. if (!prom_read_ok) {
  98. _dev->get_semaphore()->give();
  99. return false;
  100. }
  101. printf("%s found on bus %u address 0x%02x\n", name, _dev->bus_num(), _dev->get_bus_address());
  102. // Save factory calibration coefficients
  103. _cal_reg.c1 = prom[1];
  104. _cal_reg.c2 = prom[2];
  105. _cal_reg.c3 = prom[3];
  106. _cal_reg.c4 = prom[4];
  107. _cal_reg.c5 = prom[5];
  108. _cal_reg.c6 = prom[6];
  109. // Send a command to read temperature first
  110. _dev->transfer(&ADDR_CMD_CONVERT_TEMPERATURE, 1, nullptr, 0);
  111. _state = 0;
  112. memset(&_accum, 0, sizeof(_accum));
  113. _instance = _frontend.register_sensor();
  114. if (_ms56xx_type == BARO_MS5837) {
  115. _frontend.set_type(_instance, AP_Baro::BARO_TYPE_WATER);
  116. }
  117. // lower retries for run
  118. _dev->set_retries(3);
  119. _dev->get_semaphore()->give();
  120. /* Request 100Hz update */
  121. _dev->register_periodic_callback(10 * AP_USEC_PER_MSEC,
  122. FUNCTOR_BIND_MEMBER(&AP_Baro_MS56XX::_timer, void));
  123. return true;
  124. }
  125. uint16_t AP_Baro_MS56XX::_read_prom_word(uint8_t word)
  126. {
  127. const uint8_t reg = CMD_MS56XX_PROM + (word << 1);
  128. uint8_t val[2];
  129. if (!_dev->transfer(&reg, 1, val, sizeof(val))) {
  130. return 0;
  131. }
  132. return (val[0] << 8) | val[1];
  133. }
  134. uint32_t AP_Baro_MS56XX::_read_adc()
  135. {
  136. uint8_t val[3];
  137. if (!_dev->transfer(&CMD_MS56XX_READ_ADC, 1, val, sizeof(val))) {
  138. return 0;
  139. }
  140. return (val[0] << 16) | (val[1] << 8) | val[2];
  141. }
  142. bool AP_Baro_MS56XX::_read_prom_5611(uint16_t prom[8])
  143. {
  144. /*
  145. * MS5611-01BA datasheet, CYCLIC REDUNDANCY CHECK (CRC): "MS5611-01BA
  146. * contains a PROM memory with 128-Bit. A 4-bit CRC has been implemented
  147. * to check the data validity in memory."
  148. *
  149. * CRC field must me removed for CRC-4 calculation.
  150. */
  151. bool all_zero = true;
  152. for (uint8_t i = 0; i < 8; i++) {
  153. prom[i] = _read_prom_word(i);
  154. if (prom[i] != 0) {
  155. all_zero = false;
  156. }
  157. }
  158. if (all_zero) {
  159. return false;
  160. }
  161. /* save the read crc */
  162. const uint16_t crc_read = prom[7] & 0xf;
  163. /* remove CRC byte */
  164. prom[7] &= 0xff00;
  165. return crc_read == crc_crc4(prom);
  166. }
  167. bool AP_Baro_MS56XX::_read_prom_5637(uint16_t prom[8])
  168. {
  169. /*
  170. * MS5637-02BA03 datasheet, CYCLIC REDUNDANCY CHECK (CRC): "MS5637
  171. * contains a PROM memory with 112-Bit. A 4-bit CRC has been implemented
  172. * to check the data validity in memory."
  173. *
  174. * 8th PROM word must be zeroed and CRC field removed for CRC-4
  175. * calculation.
  176. */
  177. bool all_zero = true;
  178. for (uint8_t i = 0; i < 7; i++) {
  179. prom[i] = _read_prom_word(i);
  180. if (prom[i] != 0) {
  181. all_zero = false;
  182. }
  183. }
  184. if (all_zero) {
  185. return false;
  186. }
  187. prom[7] = 0;
  188. /* save the read crc */
  189. const uint16_t crc_read = (prom[0] & 0xf000) >> 12;
  190. /* remove CRC byte */
  191. prom[0] &= ~0xf000;
  192. return crc_read == crc_crc4(prom);
  193. }
  194. /*
  195. * Read the sensor with a state machine
  196. * We read one time temperature (state=0) and then 4 times pressure (states 1-4)
  197. *
  198. * Temperature is used to calculate the compensated pressure and doesn't vary
  199. * as fast as pressure. Hence we reuse the same temperature for 4 samples of
  200. * pressure.
  201. */
  202. void AP_Baro_MS56XX::_timer(void)
  203. {
  204. uint8_t next_cmd;
  205. uint8_t next_state;
  206. uint32_t adc_val = _read_adc();
  207. /*
  208. * If read fails, re-initiate a read command for current state or we are
  209. * stuck
  210. */
  211. if (adc_val == 0) {
  212. next_state = _state;
  213. } else {
  214. next_state = (_state + 1) % 5;
  215. }
  216. next_cmd = next_state == 0 ? ADDR_CMD_CONVERT_TEMPERATURE
  217. : ADDR_CMD_CONVERT_PRESSURE;
  218. if (!_dev->transfer(&next_cmd, 1, nullptr, 0)) {
  219. return;
  220. }
  221. /* if we had a failed read we are all done */
  222. if (adc_val == 0 || adc_val == 0xFFFFFF) {
  223. // a failed read can mean the next returned value will be
  224. // corrupt, we must discard it. This copes with MISO being
  225. // pulled either high or low
  226. _discard_next = true;
  227. return;
  228. }
  229. if (_discard_next) {
  230. _discard_next = false;
  231. _state = next_state;
  232. return;
  233. }
  234. WITH_SEMAPHORE(_sem);
  235. if (_state == 0) {
  236. _update_and_wrap_accumulator(&_accum.s_D2, adc_val,
  237. &_accum.d2_count, 32);
  238. } else if (pressure_ok(adc_val)) {
  239. _update_and_wrap_accumulator(&_accum.s_D1, adc_val,
  240. &_accum.d1_count, 128);
  241. }
  242. _state = next_state;
  243. }
  244. void AP_Baro_MS56XX::_update_and_wrap_accumulator(uint32_t *accum, uint32_t val,
  245. uint8_t *count, uint8_t max_count)
  246. {
  247. *accum += val;
  248. *count += 1;
  249. if (*count == max_count) {
  250. *count = max_count / 2;
  251. *accum = *accum / 2;
  252. }
  253. }
  254. void AP_Baro_MS56XX::update()
  255. {
  256. uint32_t sD1, sD2;
  257. uint8_t d1count, d2count;
  258. {
  259. WITH_SEMAPHORE(_sem);
  260. if (_accum.d1_count == 0) {
  261. return;
  262. }
  263. sD1 = _accum.s_D1;
  264. sD2 = _accum.s_D2;
  265. d1count = _accum.d1_count;
  266. d2count = _accum.d2_count;
  267. memset(&_accum, 0, sizeof(_accum));
  268. }
  269. if (d1count != 0) {
  270. _D1 = ((float)sD1) / d1count;
  271. }
  272. if (d2count != 0) {
  273. _D2 = ((float)sD2) / d2count;
  274. }
  275. switch (_ms56xx_type) {
  276. case BARO_MS5607:
  277. _calculate_5607();
  278. break;
  279. case BARO_MS5611:
  280. _calculate_5611();
  281. break;
  282. case BARO_MS5637:
  283. _calculate_5637();
  284. break;
  285. case BARO_MS5837:
  286. _calculate_5837();
  287. }
  288. }
  289. // Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
  290. void AP_Baro_MS56XX::_calculate_5611()
  291. {
  292. float dT;
  293. float TEMP;
  294. float OFF;
  295. float SENS;
  296. // Formulas from manufacturer datasheet
  297. // sub -15c temperature compensation is not included
  298. // we do the calculations using floating point allows us to take advantage
  299. // of the averaging of D1 and D1 over multiple samples, giving us more
  300. // precision
  301. dT = _D2-(((uint32_t)_cal_reg.c5)<<8);
  302. TEMP = (dT * _cal_reg.c6)/8388608;
  303. OFF = _cal_reg.c2 * 65536.0f + (_cal_reg.c4 * dT) / 128;
  304. SENS = _cal_reg.c1 * 32768.0f + (_cal_reg.c3 * dT) / 256;
  305. if (TEMP < 0) {
  306. // second order temperature compensation when under 20 degrees C
  307. float T2 = (dT*dT) / 0x80000000;
  308. float Aux = TEMP*TEMP;
  309. float OFF2 = 2.5f*Aux;
  310. float SENS2 = 1.25f*Aux;
  311. TEMP = TEMP - T2;
  312. OFF = OFF - OFF2;
  313. SENS = SENS - SENS2;
  314. }
  315. float pressure = (_D1*SENS/2097152 - OFF)/32768;
  316. float temperature = (TEMP + 2000) * 0.01f;
  317. _copy_to_frontend(_instance, pressure, temperature);
  318. }
  319. // Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
  320. void AP_Baro_MS56XX::_calculate_5607()
  321. {
  322. float dT;
  323. float TEMP;
  324. float OFF;
  325. float SENS;
  326. // Formulas from manufacturer datasheet
  327. // sub -15c temperature compensation is not included
  328. // we do the calculations using floating point allows us to take advantage
  329. // of the averaging of D1 and D1 over multiple samples, giving us more
  330. // precision
  331. dT = _D2-(((uint32_t)_cal_reg.c5)<<8);
  332. TEMP = (dT * _cal_reg.c6)/8388608;
  333. OFF = _cal_reg.c2 * 131072.0f + (_cal_reg.c4 * dT) / 64;
  334. SENS = _cal_reg.c1 * 65536.0f + (_cal_reg.c3 * dT) / 128;
  335. if (TEMP < 0) {
  336. // second order temperature compensation when under 20 degrees C
  337. float T2 = (dT*dT) / 0x80000000;
  338. float Aux = TEMP*TEMP;
  339. float OFF2 = 61.0f*Aux/16.0f;
  340. float SENS2 = 2.0f*Aux;
  341. TEMP = TEMP - T2;
  342. OFF = OFF - OFF2;
  343. SENS = SENS - SENS2;
  344. }
  345. float pressure = (_D1*SENS/2097152 - OFF)/32768;
  346. float temperature = (TEMP + 2000) * 0.01f;
  347. _copy_to_frontend(_instance, pressure, temperature);
  348. }
  349. // Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
  350. void AP_Baro_MS56XX::_calculate_5637()
  351. {
  352. int32_t dT, TEMP;
  353. int64_t OFF, SENS;
  354. int32_t raw_pressure = _D1;
  355. int32_t raw_temperature = _D2;
  356. // Formulas from manufacturer datasheet
  357. // sub -15c temperature compensation is not included
  358. dT = raw_temperature - (((uint32_t)_cal_reg.c5) << 8);
  359. TEMP = 2000 + ((int64_t)dT * (int64_t)_cal_reg.c6) / 8388608;
  360. OFF = (int64_t)_cal_reg.c2 * (int64_t)131072 + ((int64_t)_cal_reg.c4 * (int64_t)dT) / (int64_t)64;
  361. SENS = (int64_t)_cal_reg.c1 * (int64_t)65536 + ((int64_t)_cal_reg.c3 * (int64_t)dT) / (int64_t)128;
  362. if (TEMP < 2000) {
  363. // second order temperature compensation when under 20 degrees C
  364. int32_t T2 = ((int64_t)3 * ((int64_t)dT * (int64_t)dT) / (int64_t)8589934592);
  365. int64_t aux = (TEMP - 2000) * (TEMP - 2000);
  366. int64_t OFF2 = 61 * aux / 16;
  367. int64_t SENS2 = 29 * aux / 16;
  368. TEMP = TEMP - T2;
  369. OFF = OFF - OFF2;
  370. SENS = SENS - SENS2;
  371. }
  372. int32_t pressure = ((int64_t)raw_pressure * SENS / (int64_t)2097152 - OFF) / (int64_t)32768;
  373. float temperature = TEMP * 0.01f;
  374. _copy_to_frontend(_instance, (float)pressure, temperature);
  375. }
  376. // Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
  377. void AP_Baro_MS56XX::_calculate_5837()
  378. {
  379. int32_t dT, TEMP;
  380. int64_t OFF, SENS;
  381. int32_t raw_pressure = _D1;
  382. int32_t raw_temperature = _D2;
  383. // Formulas from manufacturer datasheet
  384. // sub -15c temperature compensation is not included
  385. dT = raw_temperature - (((uint32_t)_cal_reg.c5) << 8);
  386. TEMP = 2000 + ((int64_t)dT * (int64_t)_cal_reg.c6) / 8388608;
  387. OFF = (int64_t)_cal_reg.c2 * (int64_t)65536 + ((int64_t)_cal_reg.c4 * (int64_t)dT) / (int64_t)128;
  388. SENS = (int64_t)_cal_reg.c1 * (int64_t)32768 + ((int64_t)_cal_reg.c3 * (int64_t)dT) / (int64_t)256;
  389. if (TEMP < 2000) {
  390. // second order temperature compensation when under 20 degrees C
  391. int32_t T2 = ((int64_t)3 * ((int64_t)dT * (int64_t)dT) / (int64_t)8589934592);
  392. int64_t aux = (TEMP - 2000) * (TEMP - 2000);
  393. int64_t OFF2 = 3 * aux / 2;
  394. int64_t SENS2 = 5 * aux / 8;
  395. TEMP = TEMP - T2;
  396. OFF = OFF - OFF2;
  397. SENS = SENS - SENS2;
  398. }
  399. int32_t pressure = ((int64_t)raw_pressure * SENS / (int64_t)2097152 - OFF) / (int64_t)8192;
  400. pressure = pressure * 10; // MS5837 only reports to 0.1 mbar
  401. float temperature = TEMP * 0.01f;
  402. _copy_to_frontend(_instance, (float)pressure, temperature);
  403. }