AP_Compass_BMM150.cpp 9.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329
  1. /*
  2. * Copyright (C) 2016 Intel Corporation. All rights reserved.
  3. *
  4. * This file is free software: you can redistribute it and/or modify it
  5. * under the terms of the GNU General Public License as published by the
  6. * Free Software Foundation, either version 3 of the License, or
  7. * (at your option) any later version.
  8. *
  9. * This file is distributed in the hope that it will be useful, but
  10. * WITHOUT ANY WARRANTY; without even the implied warranty of
  11. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  12. * See the GNU General Public License for more details.
  13. *
  14. * You should have received a copy of the GNU General Public License along
  15. * with this program. If not, see <http://www.gnu.org/licenses/>.
  16. */
  17. #include "AP_Compass_BMM150.h"
  18. #include <AP_HAL/AP_HAL.h>
  19. #include <utility>
  20. #include <AP_HAL/utility/sparse-endian.h>
  21. #include <AP_Math/AP_Math.h>
  22. #include <stdio.h>
  23. #define CHIP_ID_REG 0x40
  24. #define CHIP_ID_VAL 0x32
  25. #define POWER_AND_OPERATIONS_REG 0x4B
  26. #define POWER_CONTROL_VAL (1 << 0)
  27. #define SOFT_RESET (1 << 7 | 1 << 1)
  28. #define OP_MODE_SELF_TEST_ODR_REG 0x4C
  29. #define NORMAL_MODE (0 << 1)
  30. #define ODR_30HZ (1 << 3 | 1 << 4 | 1 << 5)
  31. #define ODR_20HZ (1 << 3 | 0 << 4 | 1 << 5)
  32. #define DATA_X_LSB_REG 0x42
  33. #define REPETITIONS_XY_REG 0x51
  34. #define REPETITIONS_Z_REG 0X52
  35. /* Trim registers */
  36. #define DIG_X1_REG 0x5D
  37. #define DIG_Y1_REG 0x5E
  38. #define DIG_Z4_LSB_REG 0x62
  39. #define DIG_Z4_MSB_REG 0x63
  40. #define DIG_X2_REG 0x64
  41. #define DIG_Y2_REG 0x65
  42. #define DIG_Z2_LSB_REG 0x68
  43. #define DIG_Z2_MSB_REG 0x69
  44. #define DIG_Z1_LSB_REG 0x6A
  45. #define DIG_Z1_MSB_REG 0x6B
  46. #define DIG_XYZ1_LSB_REG 0x6C
  47. #define DIG_XYZ1_MSB_REG 0x6D
  48. #define DIG_Z3_LSB_REG 0x6E
  49. #define DIG_Z3_MSB_REG 0x6F
  50. #define DIG_XY2_REG 0x70
  51. #define DIG_XY1_REG 0x71
  52. #define MEASURE_TIME_USEC 16667
  53. extern const AP_HAL::HAL &hal;
  54. AP_Compass_Backend *AP_Compass_BMM150::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev, enum Rotation rotation)
  55. {
  56. if (!dev) {
  57. return nullptr;
  58. }
  59. AP_Compass_BMM150 *sensor = new AP_Compass_BMM150(std::move(dev), rotation);
  60. if (!sensor || !sensor->init()) {
  61. delete sensor;
  62. return nullptr;
  63. }
  64. return sensor;
  65. }
  66. AP_Compass_BMM150::AP_Compass_BMM150(AP_HAL::OwnPtr<AP_HAL::Device> dev, enum Rotation rotation)
  67. : _dev(std::move(dev)), _rotation(rotation)
  68. {
  69. }
  70. bool AP_Compass_BMM150::_load_trim_values()
  71. {
  72. struct {
  73. int8_t dig_x1;
  74. int8_t dig_y1;
  75. uint8_t rsv[3];
  76. le16_t dig_z4;
  77. int8_t dig_x2;
  78. int8_t dig_y2;
  79. uint8_t rsv2[2];
  80. le16_t dig_z2;
  81. le16_t dig_z1;
  82. le16_t dig_xyz1;
  83. le16_t dig_z3;
  84. int8_t dig_xy2;
  85. uint8_t dig_xy1;
  86. } PACKED trim_registers, trim_registers2;
  87. // read the registers twice to confirm we have the right
  88. // values. There is no CRC in the registers and these values are
  89. // vital to correct operation
  90. int8_t tries = 4;
  91. while (tries--) {
  92. if (!_dev->read_registers(DIG_X1_REG, (uint8_t *)&trim_registers,
  93. sizeof(trim_registers))) {
  94. continue;
  95. }
  96. if (!_dev->read_registers(DIG_X1_REG, (uint8_t *)&trim_registers2,
  97. sizeof(trim_registers))) {
  98. continue;
  99. }
  100. if (memcmp(&trim_registers, &trim_registers2, sizeof(trim_registers)) == 0) {
  101. break;
  102. }
  103. }
  104. if (-1 == tries) {
  105. hal.console->printf("BMM150: Failed to load trim registers\n");
  106. return false;
  107. }
  108. _dig.x1 = trim_registers.dig_x1;
  109. _dig.x2 = trim_registers.dig_x2;
  110. _dig.xy1 = trim_registers.dig_xy1;
  111. _dig.xy2 = trim_registers.dig_xy2;
  112. _dig.xyz1 = le16toh(trim_registers.dig_xyz1);
  113. _dig.y1 = trim_registers.dig_y1;
  114. _dig.y2 = trim_registers.dig_y2;
  115. _dig.z1 = le16toh(trim_registers.dig_z1);
  116. _dig.z2 = le16toh(trim_registers.dig_z2);
  117. _dig.z3 = le16toh(trim_registers.dig_z3);
  118. _dig.z4 = le16toh(trim_registers.dig_z4);
  119. return true;
  120. }
  121. bool AP_Compass_BMM150::init()
  122. {
  123. uint8_t val = 0;
  124. bool ret;
  125. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  126. hal.console->printf("BMM150: Unable to get bus semaphore\n");
  127. return false;
  128. }
  129. // 10 retries for init
  130. _dev->set_retries(10);
  131. // use checked registers to cope with bus errors
  132. _dev->setup_checked_registers(4);
  133. int8_t boot_tries = 4;
  134. while (boot_tries--) {
  135. /* Do a soft reset */
  136. ret = _dev->write_register(POWER_AND_OPERATIONS_REG, SOFT_RESET);
  137. hal.scheduler->delay(2);
  138. if (!ret) {
  139. continue;
  140. }
  141. /* Change power state from suspend mode to sleep mode */
  142. ret = _dev->write_register(POWER_AND_OPERATIONS_REG, POWER_CONTROL_VAL, true);
  143. hal.scheduler->delay(2);
  144. if (!ret) {
  145. continue;
  146. }
  147. ret = _dev->read_registers(CHIP_ID_REG, &val, 1);
  148. if (!ret) {
  149. continue;
  150. }
  151. if (val == CHIP_ID_VAL) {
  152. // found it
  153. break;
  154. }
  155. if (boot_tries == 0) {
  156. hal.console->printf("BMM150: Wrong chip ID 0x%02x should be 0x%02x\n", val, CHIP_ID_VAL);
  157. }
  158. }
  159. if (-1 == boot_tries) {
  160. goto bus_error;
  161. }
  162. ret = _load_trim_values();
  163. if (!ret) {
  164. goto bus_error;
  165. }
  166. /*
  167. * Recommended preset for high accuracy:
  168. * - Rep X/Y = 47
  169. * - Rep Z = 83
  170. * - ODR = 20
  171. * But we are going to use 30Hz of ODR
  172. */
  173. ret = _dev->write_register(REPETITIONS_XY_REG, (47 - 1) / 2, true);
  174. if (!ret) {
  175. goto bus_error;
  176. }
  177. ret = _dev->write_register(REPETITIONS_Z_REG, 83 - 1, true);
  178. if (!ret) {
  179. goto bus_error;
  180. }
  181. /* Change operation mode from sleep to normal and set ODR */
  182. ret = _dev->write_register(OP_MODE_SELF_TEST_ODR_REG, NORMAL_MODE | ODR_30HZ, true);
  183. if (!ret) {
  184. goto bus_error;
  185. }
  186. _dev->get_semaphore()->give();
  187. /* register the compass instance in the frontend */
  188. _compass_instance = register_compass();
  189. set_rotation(_compass_instance, _rotation);
  190. _dev->set_device_type(DEVTYPE_BMM150);
  191. set_dev_id(_compass_instance, _dev->get_bus_id());
  192. _perf_err = hal.util->perf_alloc(AP_HAL::Util::PC_COUNT, "BMM150_err");
  193. // 2 retries for run
  194. _dev->set_retries(2);
  195. _dev->register_periodic_callback(MEASURE_TIME_USEC,
  196. FUNCTOR_BIND_MEMBER(&AP_Compass_BMM150::_update, void));
  197. _last_read_ms = AP_HAL::millis();
  198. return true;
  199. bus_error:
  200. hal.console->printf("BMM150: Bus communication error\n");
  201. _dev->get_semaphore()->give();
  202. return false;
  203. }
  204. /*
  205. * Compensation algorithm got from https://github.com/BoschSensortec/BMM050_driver
  206. * this is not explained in datasheet.
  207. */
  208. int16_t AP_Compass_BMM150::_compensate_xy(int16_t xy, uint32_t rhall, int32_t txy1, int32_t txy2)
  209. {
  210. int32_t inter = ((int32_t)_dig.xyz1) << 14;
  211. inter /= rhall;
  212. inter -= 0x4000;
  213. int32_t val = _dig.xy2 * ((inter * inter) >> 7);
  214. val += (inter * (((uint32_t)_dig.xy1) << 7));
  215. val >>= 9;
  216. val += 0x100000;
  217. val *= (txy2 + 0xA0);
  218. val >>= 12;
  219. val *= xy;
  220. val >>= 13;
  221. val += (txy1 << 3);
  222. return val;
  223. }
  224. int16_t AP_Compass_BMM150::_compensate_z(int16_t z, uint32_t rhall)
  225. {
  226. int32_t dividend = int32_t(z - _dig.z4) << 15;
  227. int32_t dividend2 = dividend - ((_dig.z3 * (int32_t(rhall) - int32_t(_dig.xyz1))) >> 2);
  228. int32_t divisor = int32_t(_dig.z1) * (rhall << 1);
  229. divisor += 0x8000;
  230. divisor >>= 16;
  231. divisor += _dig.z2;
  232. int16_t ret = constrain_int32(dividend2 / divisor, -0x8000, 0x8000);
  233. #if 0
  234. static uint8_t counter;
  235. if (counter++ == 0) {
  236. printf("ret=%d z=%d rhall=%u z1=%d z2=%d z3=%d z4=%d xyz1=%d dividend=%d dividend2=%d divisor=%d\n",
  237. ret, z, rhall, _dig.z1, _dig.z2, _dig.z3, _dig.z4, _dig.xyz1, dividend, dividend2, divisor);
  238. }
  239. #endif
  240. return ret;
  241. }
  242. void AP_Compass_BMM150::_update()
  243. {
  244. le16_t data[4];
  245. bool ret = _dev->read_registers(DATA_X_LSB_REG, (uint8_t *) &data, sizeof(data));
  246. /* Checking data ready status */
  247. if (!ret || !(data[3] & 0x1)) {
  248. _dev->check_next_register();
  249. uint32_t now = AP_HAL::millis();
  250. if (now - _last_read_ms > 250) {
  251. // cope with power cycle to sensor
  252. _last_read_ms = now;
  253. _dev->write_register(POWER_AND_OPERATIONS_REG, SOFT_RESET);
  254. _dev->write_register(POWER_AND_OPERATIONS_REG, POWER_CONTROL_VAL, true);
  255. hal.util->perf_count(_perf_err);
  256. }
  257. return;
  258. }
  259. const uint16_t rhall = le16toh(data[3]) >> 2;
  260. Vector3f raw_field = Vector3f{
  261. (float) _compensate_xy(((int16_t)le16toh(data[0])) >> 3,
  262. rhall, _dig.x1, _dig.x2),
  263. (float) _compensate_xy(((int16_t)le16toh(data[1])) >> 3,
  264. rhall, _dig.y1, _dig.y2),
  265. (float) _compensate_z(((int16_t)le16toh(data[2])) >> 1, rhall)};
  266. /* apply sensitivity scale 16 LSB/uT */
  267. raw_field /= 16;
  268. /* convert uT to milligauss */
  269. raw_field *= 10;
  270. _last_read_ms = AP_HAL::millis();
  271. accumulate_sample(raw_field, _compass_instance);
  272. _dev->check_next_register();
  273. }
  274. void AP_Compass_BMM150::read()
  275. {
  276. drain_accumulated_samples(_compass_instance);
  277. }