AP_Airspeed_MS5525.cpp 8.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300
  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. /*
  14. backend driver for airspeed from a I2C MS5525D0 sensor
  15. */
  16. #include "AP_Airspeed_MS5525.h"
  17. #include <stdio.h>
  18. #include <utility>
  19. #include <AP_Common/AP_Common.h>
  20. #include <AP_HAL/AP_HAL.h>
  21. #include <AP_HAL/I2CDevice.h>
  22. #include <AP_HAL/utility/sparse-endian.h>
  23. #include <AP_Math/AP_Math.h>
  24. #include <AP_Math/crc.h>
  25. extern const AP_HAL::HAL &hal;
  26. #define MS5525D0_I2C_ADDR_1 0x76
  27. #define MS5525D0_I2C_ADDR_2 0x77
  28. #define REG_RESET 0x1E
  29. #define REG_CONVERT_D1_OSR_256 0x40
  30. #define REG_CONVERT_D1_OSR_512 0x42
  31. #define REG_CONVERT_D1_OSR_1024 0x44
  32. #define REG_CONVERT_D1_OSR_2048 0x46
  33. #define REG_CONVERT_D1_OSR_4096 0x48
  34. #define REG_CONVERT_D2_OSR_256 0x50
  35. #define REG_CONVERT_D2_OSR_512 0x52
  36. #define REG_CONVERT_D2_OSR_1024 0x54
  37. #define REG_CONVERT_D2_OSR_2048 0x56
  38. #define REG_CONVERT_D2_OSR_4096 0x58
  39. #define REG_ADC_READ 0x00
  40. #define REG_PROM_BASE 0xA0
  41. // go for 1024 oversampling. This should be fast enough to reduce
  42. // noise but low enough to keep self-heating small
  43. #define REG_CONVERT_PRESSURE REG_CONVERT_D1_OSR_1024
  44. #define REG_CONVERT_TEMPERATURE REG_CONVERT_D2_OSR_1024
  45. AP_Airspeed_MS5525::AP_Airspeed_MS5525(AP_Airspeed &_frontend, uint8_t _instance, MS5525_ADDR address) :
  46. AP_Airspeed_Backend(_frontend, _instance)
  47. {
  48. _address = address;
  49. }
  50. // probe and initialise the sensor
  51. bool AP_Airspeed_MS5525::init()
  52. {
  53. const uint8_t addresses[] = { MS5525D0_I2C_ADDR_1, MS5525D0_I2C_ADDR_2 };
  54. bool found = false;
  55. for (uint8_t i=0; i<ARRAY_SIZE(addresses); i++) {
  56. if (_address != MS5525_ADDR_AUTO && i != (uint8_t)_address) {
  57. continue;
  58. }
  59. dev = hal.i2c_mgr->get_device(get_bus(), addresses[i]);
  60. if (!dev) {
  61. continue;
  62. }
  63. if (!dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  64. continue;
  65. }
  66. // lots of retries during probe
  67. dev->set_retries(5);
  68. found = read_prom();
  69. if (found) {
  70. printf("MS5525: Found sensor on bus %u address 0x%02x\n", get_bus(), addresses[i]);
  71. break;
  72. }
  73. dev->get_semaphore()->give();
  74. }
  75. if (!found) {
  76. printf("MS5525: no sensor found\n");
  77. return false;
  78. }
  79. // Send a command to read temperature first
  80. uint8_t reg = REG_CONVERT_TEMPERATURE;
  81. dev->transfer(&reg, 1, nullptr, 0);
  82. state = 0;
  83. command_send_us = AP_HAL::micros();
  84. // drop to 2 retries for runtime
  85. dev->set_retries(2);
  86. dev->get_semaphore()->give();
  87. // read at 80Hz
  88. dev->register_periodic_callback(1000000UL/80U,
  89. FUNCTOR_BIND_MEMBER(&AP_Airspeed_MS5525::timer, void));
  90. return true;
  91. }
  92. /**
  93. * CRC used by MS pressure devices
  94. */
  95. uint16_t AP_Airspeed_MS5525::crc4_prom(void)
  96. {
  97. return crc_crc4(prom);
  98. }
  99. bool AP_Airspeed_MS5525::read_prom(void)
  100. {
  101. // reset the chip to ensure it has correct prom values loaded
  102. uint8_t reg = REG_RESET;
  103. if (!dev->transfer(&reg, 1, nullptr, 0)) {
  104. return false;
  105. }
  106. hal.scheduler->delay(5);
  107. bool all_zero = true;
  108. for (uint8_t i = 0; i < 8; i++) {
  109. be16_t val;
  110. if (!dev->read_registers(REG_PROM_BASE+i*2, (uint8_t *) &val,
  111. sizeof(uint16_t))) {
  112. return false;
  113. }
  114. prom[i] = be16toh(val);
  115. if (prom[i] != 0) {
  116. all_zero = false;
  117. }
  118. }
  119. if (all_zero) {
  120. return false;
  121. }
  122. /* save the read crc */
  123. const uint16_t crc_read = prom[7] & 0xf;
  124. /* remove CRC byte */
  125. prom[7] &= 0xff00;
  126. uint16_t crc_calc = crc4_prom();
  127. if (crc_read != crc_calc) {
  128. printf("MS5525: CRC mismatch 0x%04x 0x%04x\n", crc_read, crc_calc);
  129. }
  130. return crc_read == crc_calc;
  131. }
  132. /*
  133. read from the ADC
  134. */
  135. int32_t AP_Airspeed_MS5525::read_adc()
  136. {
  137. uint8_t val[3];
  138. if (!dev->read_registers(REG_ADC_READ, val, 3)) {
  139. return 0;
  140. }
  141. return (val[0] << 16) | (val[1] << 8) | val[2];
  142. }
  143. /*
  144. calculate pressure and temperature
  145. */
  146. void AP_Airspeed_MS5525::calculate(void)
  147. {
  148. // table for the 001DS part, 1PSI range
  149. const uint8_t Q1 = 15;
  150. const uint8_t Q2 = 17;
  151. const uint8_t Q3 = 7;
  152. const uint8_t Q4 = 5;
  153. const uint8_t Q5 = 7;
  154. const uint8_t Q6 = 21;
  155. int64_t dT = D2 - int64_t(prom[5]) * (1UL<<Q5);
  156. int64_t TEMP = 2000 + (dT*int64_t(prom[6]))/(1UL<<Q6);
  157. int64_t OFF = int64_t(prom[2])*(1UL<<Q2) + (int64_t(prom[4])*dT)/(1UL<<Q4);
  158. int64_t SENS = int64_t(prom[1])*(1UL<<Q1) + (int64_t(prom[3])*dT)/(1UL<<Q3);
  159. int64_t P = (D1*SENS/(1UL<<21)-OFF)/(1UL<<15);
  160. const float PSI_to_Pa = 6894.757f;
  161. float P_Pa = PSI_to_Pa * 1.0e-4 * P;
  162. float Temp_C = TEMP * 0.01;
  163. #if 0
  164. static uint16_t counter;
  165. if (counter++ == 100) {
  166. printf("P=%.6f T=%.2f D1=%d D2=%d\n", P_Pa, Temp_C, D1, D2);
  167. counter=0;
  168. }
  169. #endif
  170. WITH_SEMAPHORE(sem);
  171. pressure_sum += P_Pa;
  172. temperature_sum += Temp_C;
  173. press_count++;
  174. temp_count++;
  175. last_sample_time_ms = AP_HAL::millis();
  176. }
  177. // 80Hz timer
  178. void AP_Airspeed_MS5525::timer()
  179. {
  180. if (AP_HAL::micros() - command_send_us < 10000) {
  181. // we should avoid trying to read the ADC too soon after
  182. // sending the command
  183. return;
  184. }
  185. uint32_t adc_val = read_adc();
  186. if (adc_val == 0) {
  187. // we have either done a read too soon after sending the
  188. // request or we have tried to read the same sample twice. We
  189. // re-send the command now as we don't know what state the
  190. // sensor is in, and we do want to trigger it sending a value,
  191. // which we will discard
  192. if (dev->transfer(&cmd_sent, 1, nullptr, 0)) {
  193. command_send_us = AP_HAL::micros();
  194. }
  195. // when we get adc_val == 0 then then both the current value and
  196. // the next value we read from the sensor are invalid
  197. ignore_next = true;
  198. return;
  199. }
  200. /*
  201. * If read fails, re-initiate a read command for current state or we are
  202. * stuck
  203. */
  204. if (!ignore_next) {
  205. if (cmd_sent == REG_CONVERT_TEMPERATURE) {
  206. D2 = adc_val;
  207. } else if (cmd_sent == REG_CONVERT_PRESSURE) {
  208. D1 = adc_val;
  209. calculate();
  210. }
  211. }
  212. ignore_next = false;
  213. cmd_sent = (state == 0) ? REG_CONVERT_TEMPERATURE : REG_CONVERT_PRESSURE;
  214. if (!dev->transfer(&cmd_sent, 1, nullptr, 0)) {
  215. // we don't know for sure what state the sensor is in when we
  216. // fail to send the command, so ignore the next response
  217. ignore_next = true;
  218. return;
  219. }
  220. command_send_us = AP_HAL::micros();
  221. state = (state + 1) % 5;
  222. }
  223. // return the current differential_pressure in Pascal
  224. bool AP_Airspeed_MS5525::get_differential_pressure(float &_pressure)
  225. {
  226. if ((AP_HAL::millis() - last_sample_time_ms) > 100) {
  227. return false;
  228. }
  229. WITH_SEMAPHORE(sem);
  230. if (press_count > 0) {
  231. pressure = pressure_sum / press_count;
  232. press_count = 0;
  233. pressure_sum = 0;
  234. }
  235. _pressure = pressure;
  236. return true;
  237. }
  238. // return the current temperature in degrees C, if available
  239. bool AP_Airspeed_MS5525::get_temperature(float &_temperature)
  240. {
  241. if ((AP_HAL::millis() - last_sample_time_ms) > 100) {
  242. return false;
  243. }
  244. WITH_SEMAPHORE(sem);
  245. if (temp_count > 0) {
  246. temperature = temperature_sum / temp_count;
  247. temp_count = 0;
  248. temperature_sum = 0;
  249. }
  250. _temperature = temperature;
  251. return true;
  252. }