AP_Baro_ICM20789.cpp 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359
  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_HAL/AP_HAL.h>
  14. #include <AP_HAL/I2CDevice.h>
  15. #include <utility>
  16. #include <AP_Common/AP_Common.h>
  17. #include <AP_HAL/AP_HAL.h>
  18. #include <AP_Math/AP_Math.h>
  19. #include <AP_BoardConfig/AP_BoardConfig.h>
  20. #include "AP_Baro_ICM20789.h"
  21. #include <utility>
  22. #include <stdio.h>
  23. #include <AP_Math/AP_Math.h>
  24. #include <AP_Logger/AP_Logger.h>
  25. #include <AP_InertialSensor/AP_InertialSensor_Invensense_registers.h>
  26. extern const AP_HAL::HAL &hal;
  27. /*
  28. CMD_READ options. The draft datasheet doesn't specify, but it seems
  29. Mode_1 has a conversion interval of 2ms. Mode_3 has a conversion
  30. interval of 20ms. Both seem to produce equally as smooth results, so
  31. presumably Mode_3 is doing internal averaging
  32. */
  33. #define CMD_READ_PT_MODE_1 0x401A
  34. #define CMD_READ_PT_MODE_3 0x5059
  35. #define CMD_READ_TP_MODE_1 0x609C
  36. #define CMD_READ_TP_MODE_3 0x70DF
  37. #define CONVERSION_INTERVAL_MODE_1 2000
  38. #define CONVERSION_INTERVAL_MODE_3 20000
  39. // setup for Mode_3
  40. #define CMD_READ_PT CMD_READ_PT_MODE_3
  41. #define CONVERSION_INTERVAL CONVERSION_INTERVAL_MODE_3
  42. #define CMD_SOFT_RESET 0x805D
  43. #define CMD_READ_ID 0xEFC8
  44. #define BARO_ICM20789_DEBUG 0
  45. #if BARO_ICM20789_DEBUG
  46. #define debug(fmt, args...) hal.console->printf(fmt, ##args)
  47. #else
  48. #define debug(fmt, args...)
  49. #endif
  50. /*
  51. constructor
  52. */
  53. AP_Baro_ICM20789::AP_Baro_ICM20789(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev, AP_HAL::OwnPtr<AP_HAL::Device> _dev_imu)
  54. : AP_Baro_Backend(baro)
  55. , dev(std::move(_dev))
  56. , dev_imu(std::move(_dev_imu))
  57. {
  58. }
  59. AP_Baro_Backend *AP_Baro_ICM20789::probe(AP_Baro &baro,
  60. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
  61. AP_HAL::OwnPtr<AP_HAL::Device> dev_imu)
  62. {
  63. debug("Probing for ICM20789 baro\n");
  64. if (!dev || !dev_imu) {
  65. return nullptr;
  66. }
  67. AP_Baro_ICM20789 *sensor = new AP_Baro_ICM20789(baro, std::move(dev), std::move(dev_imu));
  68. if (!sensor || !sensor->init()) {
  69. delete sensor;
  70. return nullptr;
  71. }
  72. return sensor;
  73. }
  74. /*
  75. setup ICM20789 to enable barometer, assuming IMU is on SPI and baro is on I2C
  76. */
  77. bool AP_Baro_ICM20789::imu_spi_init(void)
  78. {
  79. if (!dev_imu->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  80. AP_HAL::panic("PANIC: AP_Baro_ICM20789: failed to take serial semaphore ICM");
  81. }
  82. dev_imu->set_read_flag(0x80);
  83. dev_imu->set_speed(AP_HAL::Device::SPEED_LOW);
  84. uint8_t whoami = 0;
  85. uint8_t v;
  86. dev_imu->read_registers(MPUREG_USER_CTRL, &v, 1);
  87. dev_imu->write_register(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_XGYRO);
  88. hal.scheduler->delay(1);
  89. dev_imu->write_register(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);
  90. dev_imu->write_register(MPUREG_PWR_MGMT_1,
  91. BIT_PWR_MGMT_1_SLEEP | BIT_PWR_MGMT_1_CLK_XGYRO);
  92. hal.scheduler->delay(1);
  93. dev_imu->write_register(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_XGYRO);
  94. hal.scheduler->delay(1);
  95. dev_imu->write_register(MPUREG_FIFO_EN, 0x00);
  96. dev_imu->write_register(MPUREG_PWR_MGMT_1,
  97. BIT_PWR_MGMT_1_SLEEP | BIT_PWR_MGMT_1_CLK_XGYRO);
  98. dev_imu->read_registers(MPUREG_WHOAMI, &whoami, 1);
  99. // wait for sensor to settle
  100. hal.scheduler->delay(100);
  101. dev_imu->read_registers(MPUREG_WHOAMI, &whoami, 1);
  102. dev_imu->write_register(MPUREG_INT_PIN_CFG, 0x00);
  103. dev_imu->write_register(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);
  104. dev_imu->get_semaphore()->give();
  105. return true;
  106. }
  107. /*
  108. setup ICM20789 to enable barometer, assuming both IMU and baro on the same i2c bus
  109. */
  110. bool AP_Baro_ICM20789::imu_i2c_init(void)
  111. {
  112. // as the baro device is already locked we need to re-use it,
  113. // changing its address to match the IMU address
  114. uint8_t old_address = dev->get_bus_address();
  115. dev->set_address(dev_imu->get_bus_address());
  116. dev->set_retries(4);
  117. uint8_t whoami=0;
  118. dev->read_registers(MPUREG_WHOAMI, &whoami, 1);
  119. debug("ICM20789: whoami 0x%02x old_address=%02x\n", whoami, old_address);
  120. dev->write_register(MPUREG_FIFO_EN, 0x00);
  121. dev->write_register(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_XGYRO);
  122. // wait for sensor to settle
  123. hal.scheduler->delay(10);
  124. dev->write_register(MPUREG_INT_PIN_CFG, BIT_BYPASS_EN);
  125. dev->set_address(old_address);
  126. return true;
  127. }
  128. bool AP_Baro_ICM20789::init()
  129. {
  130. if (!dev) {
  131. return false;
  132. }
  133. debug("Looking for 20789 baro\n");
  134. if (!dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  135. AP_HAL::panic("PANIC: AP_Baro_ICM20789: failed to take serial semaphore for init");
  136. }
  137. debug("Setting up IMU\n");
  138. if (dev_imu->bus_type() != AP_HAL::Device::BUS_TYPE_I2C) {
  139. if (!imu_spi_init()) {
  140. debug("ICM20789: failed to initialise IMU SPI device\n");
  141. return false;
  142. }
  143. } else if (!imu_i2c_init()) {
  144. debug("ICM20789: failed to initialise IMU I2C device\n");
  145. return false;
  146. }
  147. if (!send_cmd16(CMD_SOFT_RESET)) {
  148. debug("ICM20789: reset failed\n");
  149. goto failed;
  150. }
  151. // wait for sensor to settle
  152. hal.scheduler->delay(10);
  153. if (!read_calibration_data()) {
  154. debug("ICM20789: read_calibration_data failed\n");
  155. goto failed;
  156. }
  157. // start a reading
  158. if (!send_cmd16(CMD_READ_PT)) {
  159. debug("ICM20789: start read failed\n");
  160. goto failed;
  161. }
  162. dev->set_retries(0);
  163. instance = _frontend.register_sensor();
  164. dev->get_semaphore()->give();
  165. debug("ICM20789: startup OK\n");
  166. // use 10ms to ensure we don't lose samples, with max lag of 10ms
  167. dev->register_periodic_callback(CONVERSION_INTERVAL/2, FUNCTOR_BIND_MEMBER(&AP_Baro_ICM20789::timer, void));
  168. return true;
  169. failed:
  170. dev->get_semaphore()->give();
  171. return false;
  172. }
  173. bool AP_Baro_ICM20789::send_cmd16(uint16_t cmd)
  174. {
  175. uint8_t cmd_b[2] = { uint8_t(cmd >> 8), uint8_t(cmd & 0xFF) };
  176. return dev->transfer(cmd_b, 2, nullptr, 0);
  177. }
  178. bool AP_Baro_ICM20789::read_calibration_data(void)
  179. {
  180. // setup for OTP read
  181. const uint8_t cmd[5] = { 0xC5, 0x95, 0x00, 0x66, 0x9C };
  182. if (!dev->transfer(cmd, sizeof(cmd), nullptr, 0)) {
  183. debug("ICM20789: read cal1 failed\n");
  184. return false;
  185. }
  186. for (uint8_t i=0; i<4; i++) {
  187. if (!send_cmd16(0xC7F7)) {
  188. debug("ICM20789: read cal2[%u] failed\n", i);
  189. return false;
  190. }
  191. uint8_t d[3];
  192. if (!dev->transfer(nullptr, 0, d, sizeof(d))) {
  193. debug("ICM20789: read cal3[%u] failed\n", i);
  194. return false;
  195. }
  196. sensor_constants[i] = int16_t((d[0]<<8) | d[1]);
  197. debug("sensor_constants[%u]=%d\n", i, sensor_constants[i]);
  198. }
  199. return true;
  200. }
  201. void AP_Baro_ICM20789::calculate_conversion_constants(const float p_Pa[3], const float p_LUT[3],
  202. float &A, float &B, float &C)
  203. {
  204. C = (p_LUT[0] * p_LUT[1] * (p_Pa[0] - p_Pa[1]) +
  205. p_LUT[1] * p_LUT[2] * (p_Pa[1] - p_Pa[2]) +
  206. p_LUT[2] * p_LUT[0] * (p_Pa[2] - p_Pa[0])) /
  207. (p_LUT[2] * (p_Pa[0] - p_Pa[1]) +
  208. p_LUT[0] * (p_Pa[1] - p_Pa[2]) +
  209. p_LUT[1] * (p_Pa[2] - p_Pa[0]));
  210. A = (p_Pa[0] * p_LUT[0] - p_Pa[1] * p_LUT[1] - (p_Pa[1] - p_Pa[0]) * C) / (p_LUT[0] - p_LUT[1]);
  211. B = (p_Pa[0] - A) * (p_LUT[0] + C);
  212. }
  213. /*
  214. Convert an output from a calibrated sensor to a pressure in Pa.
  215. Arguments:
  216. p_LSB -- Raw pressure data from sensor
  217. T_LSB -- Raw temperature data from sensor
  218. */
  219. float AP_Baro_ICM20789::get_pressure(uint32_t p_LSB, uint32_t T_LSB)
  220. {
  221. float t = T_LSB - 32768.0;
  222. float s[3];
  223. s[0] = LUT_lower + float(sensor_constants[0] * t * t) * quadr_factor;
  224. s[1] = offst_factor * sensor_constants[3] + float(sensor_constants[1] * t * t) * quadr_factor;
  225. s[2] = LUT_upper + float(sensor_constants[2] * t * t) * quadr_factor;
  226. float A, B, C;
  227. calculate_conversion_constants(p_Pa_calib, s, A, B, C);
  228. return A + B / (C + p_LSB);
  229. }
  230. #if BARO_ICM20789_DEBUG
  231. static struct {
  232. uint32_t Praw, Traw;
  233. float T, P;
  234. } dd;
  235. #endif
  236. void AP_Baro_ICM20789::convert_data(uint32_t Praw, uint32_t Traw)
  237. {
  238. // temperature is easy
  239. float T = -45 + (175.0f / (1U<<16)) * Traw;
  240. // pressure involves a few more calculations
  241. float P = get_pressure(Praw, Traw);
  242. if (!pressure_ok(P)) {
  243. return;
  244. }
  245. WITH_SEMAPHORE(_sem);
  246. #if BARO_ICM20789_DEBUG
  247. dd.Praw = Praw;
  248. dd.Traw = Traw;
  249. dd.P = P;
  250. dd.T = T;
  251. #endif
  252. accum.psum += P;
  253. accum.tsum += T;
  254. accum.count++;
  255. }
  256. void AP_Baro_ICM20789::timer(void)
  257. {
  258. uint8_t d[9] {};
  259. if (dev->transfer(nullptr, 0, d, sizeof(d))) {
  260. // ignore CRC bytes for now
  261. uint32_t Praw = (uint32_t(d[0]) << 16) | (uint32_t(d[1]) << 8) | d[3];
  262. uint32_t Traw = (uint32_t(d[6]) << 8) | d[7];
  263. convert_data(Praw, Traw);
  264. send_cmd16(CMD_READ_PT);
  265. last_measure_us = AP_HAL::micros();
  266. } else {
  267. if (AP_HAL::micros() - last_measure_us > CONVERSION_INTERVAL*3) {
  268. // lost a sample
  269. send_cmd16(CMD_READ_PT);
  270. last_measure_us = AP_HAL::micros();
  271. }
  272. }
  273. }
  274. void AP_Baro_ICM20789::update()
  275. {
  276. #if BARO_ICM20789_DEBUG
  277. // useful for debugging
  278. AP::logger().Write("ICMB", "TimeUS,Traw,Praw,P,T", "QIIff",
  279. AP_HAL::micros64(),
  280. dd.Traw, dd.Praw, dd.P, dd.T);
  281. #endif
  282. WITH_SEMAPHORE(_sem);
  283. if (accum.count > 0) {
  284. _copy_to_frontend(instance, accum.psum/accum.count, accum.tsum/accum.count);
  285. accum.psum = accum.tsum = 0;
  286. accum.count = 0;
  287. }
  288. }