AP_Compass_LSM303D.cpp 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432
  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 <utility>
  14. #include <AP_HAL/AP_HAL.h>
  15. #include <AP_Math/AP_Math.h>
  16. #include "AP_Compass_LSM303D.h"
  17. extern const AP_HAL::HAL &hal;
  18. #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
  19. #include <AP_HAL_Linux/GPIO.h>
  20. #endif
  21. #ifndef LSM303D_DRDY_M_PIN
  22. #define LSM303D_DRDY_M_PIN -1
  23. #endif
  24. /* SPI protocol address bits */
  25. #define DIR_READ (1<<7)
  26. #define DIR_WRITE (0<<7)
  27. #define ADDR_INCREMENT (1<<6)
  28. /* register addresses: A: accel, M: mag, T: temp */
  29. #define ADDR_WHO_AM_I 0x0F
  30. #define WHO_I_AM 0x49
  31. #define ADDR_OUT_TEMP_L 0x05
  32. #define ADDR_OUT_TEMP_H 0x06
  33. #define ADDR_STATUS_M 0x07
  34. #define ADDR_OUT_X_L_M 0x08
  35. #define ADDR_OUT_X_H_M 0x09
  36. #define ADDR_OUT_Y_L_M 0x0A
  37. #define ADDR_OUT_Y_H_M 0x0B
  38. #define ADDR_OUT_Z_L_M 0x0C
  39. #define ADDR_OUT_Z_H_M 0x0D
  40. #define ADDR_INT_CTRL_M 0x12
  41. #define ADDR_INT_SRC_M 0x13
  42. #define ADDR_REFERENCE_X 0x1c
  43. #define ADDR_REFERENCE_Y 0x1d
  44. #define ADDR_REFERENCE_Z 0x1e
  45. #define ADDR_STATUS_A 0x27
  46. #define ADDR_OUT_X_L_A 0x28
  47. #define ADDR_OUT_X_H_A 0x29
  48. #define ADDR_OUT_Y_L_A 0x2A
  49. #define ADDR_OUT_Y_H_A 0x2B
  50. #define ADDR_OUT_Z_L_A 0x2C
  51. #define ADDR_OUT_Z_H_A 0x2D
  52. #define ADDR_CTRL_REG0 0x1F
  53. #define ADDR_CTRL_REG1 0x20
  54. #define ADDR_CTRL_REG2 0x21
  55. #define ADDR_CTRL_REG3 0x22
  56. #define ADDR_CTRL_REG4 0x23
  57. #define ADDR_CTRL_REG5 0x24
  58. #define ADDR_CTRL_REG6 0x25
  59. #define ADDR_CTRL_REG7 0x26
  60. #define ADDR_FIFO_CTRL 0x2e
  61. #define ADDR_FIFO_SRC 0x2f
  62. #define ADDR_IG_CFG1 0x30
  63. #define ADDR_IG_SRC1 0x31
  64. #define ADDR_IG_THS1 0x32
  65. #define ADDR_IG_DUR1 0x33
  66. #define ADDR_IG_CFG2 0x34
  67. #define ADDR_IG_SRC2 0x35
  68. #define ADDR_IG_THS2 0x36
  69. #define ADDR_IG_DUR2 0x37
  70. #define ADDR_CLICK_CFG 0x38
  71. #define ADDR_CLICK_SRC 0x39
  72. #define ADDR_CLICK_THS 0x3a
  73. #define ADDR_TIME_LIMIT 0x3b
  74. #define ADDR_TIME_LATENCY 0x3c
  75. #define ADDR_TIME_WINDOW 0x3d
  76. #define ADDR_ACT_THS 0x3e
  77. #define ADDR_ACT_DUR 0x3f
  78. #define REG1_RATE_BITS_A ((1<<7) | (1<<6) | (1<<5) | (1<<4))
  79. #define REG1_POWERDOWN_A ((0<<7) | (0<<6) | (0<<5) | (0<<4))
  80. #define REG1_RATE_3_125HZ_A ((0<<7) | (0<<6) | (0<<5) | (1<<4))
  81. #define REG1_RATE_6_25HZ_A ((0<<7) | (0<<6) | (1<<5) | (0<<4))
  82. #define REG1_RATE_12_5HZ_A ((0<<7) | (0<<6) | (1<<5) | (1<<4))
  83. #define REG1_RATE_25HZ_A ((0<<7) | (1<<6) | (0<<5) | (0<<4))
  84. #define REG1_RATE_50HZ_A ((0<<7) | (1<<6) | (0<<5) | (1<<4))
  85. #define REG1_RATE_100HZ_A ((0<<7) | (1<<6) | (1<<5) | (0<<4))
  86. #define REG1_RATE_200HZ_A ((0<<7) | (1<<6) | (1<<5) | (1<<4))
  87. #define REG1_RATE_400HZ_A ((1<<7) | (0<<6) | (0<<5) | (0<<4))
  88. #define REG1_RATE_800HZ_A ((1<<7) | (0<<6) | (0<<5) | (1<<4))
  89. #define REG1_RATE_1600HZ_A ((1<<7) | (0<<6) | (1<<5) | (0<<4))
  90. #define REG1_BDU_UPDATE (1<<3)
  91. #define REG1_Z_ENABLE_A (1<<2)
  92. #define REG1_Y_ENABLE_A (1<<1)
  93. #define REG1_X_ENABLE_A (1<<0)
  94. #define REG2_ANTIALIAS_FILTER_BW_BITS_A ((1<<7) | (1<<6))
  95. #define REG2_AA_FILTER_BW_773HZ_A ((0<<7) | (0<<6))
  96. #define REG2_AA_FILTER_BW_194HZ_A ((0<<7) | (1<<6))
  97. #define REG2_AA_FILTER_BW_362HZ_A ((1<<7) | (0<<6))
  98. #define REG2_AA_FILTER_BW_50HZ_A ((1<<7) | (1<<6))
  99. #define REG2_FULL_SCALE_BITS_A ((1<<5) | (1<<4) | (1<<3))
  100. #define REG2_FULL_SCALE_2G_A ((0<<5) | (0<<4) | (0<<3))
  101. #define REG2_FULL_SCALE_4G_A ((0<<5) | (0<<4) | (1<<3))
  102. #define REG2_FULL_SCALE_6G_A ((0<<5) | (1<<4) | (0<<3))
  103. #define REG2_FULL_SCALE_8G_A ((0<<5) | (1<<4) | (1<<3))
  104. #define REG2_FULL_SCALE_16G_A ((1<<5) | (0<<4) | (0<<3))
  105. #define REG5_ENABLE_T (1<<7)
  106. #define REG5_RES_HIGH_M ((1<<6) | (1<<5))
  107. #define REG5_RES_LOW_M ((0<<6) | (0<<5))
  108. #define REG5_RATE_BITS_M ((1<<4) | (1<<3) | (1<<2))
  109. #define REG5_RATE_3_125HZ_M ((0<<4) | (0<<3) | (0<<2))
  110. #define REG5_RATE_6_25HZ_M ((0<<4) | (0<<3) | (1<<2))
  111. #define REG5_RATE_12_5HZ_M ((0<<4) | (1<<3) | (0<<2))
  112. #define REG5_RATE_25HZ_M ((0<<4) | (1<<3) | (1<<2))
  113. #define REG5_RATE_50HZ_M ((1<<4) | (0<<3) | (0<<2))
  114. #define REG5_RATE_100HZ_M ((1<<4) | (0<<3) | (1<<2))
  115. #define REG5_RATE_DO_NOT_USE_M ((1<<4) | (1<<3) | (0<<2))
  116. #define REG6_FULL_SCALE_BITS_M ((1<<6) | (1<<5))
  117. #define REG6_FULL_SCALE_2GA_M ((0<<6) | (0<<5))
  118. #define REG6_FULL_SCALE_4GA_M ((0<<6) | (1<<5))
  119. #define REG6_FULL_SCALE_8GA_M ((1<<6) | (0<<5))
  120. #define REG6_FULL_SCALE_12GA_M ((1<<6) | (1<<5))
  121. #define REG7_CONT_MODE_M ((0<<1) | (0<<0))
  122. #define INT_CTRL_M 0x12
  123. #define INT_SRC_M 0x13
  124. #define LSM303D_MAG_DEFAULT_RANGE_GA 2
  125. #define LSM303D_MAG_DEFAULT_RATE 100
  126. AP_Compass_LSM303D::AP_Compass_LSM303D(AP_HAL::OwnPtr<AP_HAL::Device> dev)
  127. : _dev(std::move(dev))
  128. {
  129. }
  130. AP_Compass_Backend *AP_Compass_LSM303D::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
  131. enum Rotation rotation)
  132. {
  133. if (!dev) {
  134. return nullptr;
  135. }
  136. AP_Compass_LSM303D *sensor = new AP_Compass_LSM303D(std::move(dev));
  137. if (!sensor || !sensor->init(rotation)) {
  138. delete sensor;
  139. return nullptr;
  140. }
  141. return sensor;
  142. }
  143. uint8_t AP_Compass_LSM303D::_register_read(uint8_t reg)
  144. {
  145. uint8_t val = 0;
  146. reg |= DIR_READ;
  147. _dev->read_registers(reg, &val, 1);
  148. return val;
  149. }
  150. bool AP_Compass_LSM303D::_block_read(uint8_t reg, uint8_t *buf, uint32_t size)
  151. {
  152. reg |= DIR_READ | ADDR_INCREMENT;
  153. return _dev->read_registers(reg, buf, size);
  154. }
  155. void AP_Compass_LSM303D::_register_write(uint8_t reg, uint8_t val)
  156. {
  157. _dev->write_register(reg, val);
  158. }
  159. void AP_Compass_LSM303D::_register_modify(uint8_t reg, uint8_t clearbits, uint8_t setbits)
  160. {
  161. uint8_t val;
  162. val = _register_read(reg);
  163. val &= ~clearbits;
  164. val |= setbits;
  165. _register_write(reg, val);
  166. }
  167. /**
  168. * Return true if the LSM303D has new data available for both the mag and
  169. * the accels.
  170. */
  171. bool AP_Compass_LSM303D::_data_ready()
  172. {
  173. return _drdy_pin_m == nullptr || (_drdy_pin_m->read() != 0);
  174. }
  175. // Read Sensor data
  176. bool AP_Compass_LSM303D::_read_sample()
  177. {
  178. struct PACKED {
  179. uint8_t status;
  180. int16_t x;
  181. int16_t y;
  182. int16_t z;
  183. } rx;
  184. if (_register_read(ADDR_CTRL_REG7) != _reg7_expected) {
  185. hal.console->printf("LSM303D _read_data_transaction_accel: _reg7_expected unexpected\n");
  186. return false;
  187. }
  188. if (!_data_ready()) {
  189. return false;
  190. }
  191. if (!_block_read(ADDR_STATUS_M, (uint8_t *) &rx, sizeof(rx))) {
  192. return false;
  193. }
  194. /* check for overrun */
  195. if ((rx.status & 0x70) != 0) {
  196. return false;
  197. }
  198. if (rx.x == 0 && rx.y == 0 && rx.z == 0) {
  199. return false;
  200. }
  201. _mag_x = rx.x;
  202. _mag_y = rx.y;
  203. _mag_z = rx.z;
  204. return true;
  205. }
  206. bool AP_Compass_LSM303D::init(enum Rotation rotation)
  207. {
  208. if (LSM303D_DRDY_M_PIN >= 0) {
  209. _drdy_pin_m = hal.gpio->channel(LSM303D_DRDY_M_PIN);
  210. _drdy_pin_m->mode(HAL_GPIO_INPUT);
  211. }
  212. bool success = _hardware_init();
  213. if (!success) {
  214. return false;
  215. }
  216. _initialised = true;
  217. /* register the compass instance in the frontend */
  218. _compass_instance = register_compass();
  219. set_rotation(_compass_instance, rotation);
  220. _dev->set_device_type(DEVTYPE_LSM303D);
  221. set_dev_id(_compass_instance, _dev->get_bus_id());
  222. // read at 91Hz. We don't run at 100Hz as fetching data too fast can cause some very
  223. // odd periodic changes in the output data
  224. _dev->register_periodic_callback(11000, FUNCTOR_BIND_MEMBER(&AP_Compass_LSM303D::_update, void));
  225. return true;
  226. }
  227. bool AP_Compass_LSM303D::_hardware_init()
  228. {
  229. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  230. AP_HAL::panic("LSM303D: Unable to get semaphore");
  231. }
  232. // initially run the bus at low speed
  233. _dev->set_speed(AP_HAL::Device::SPEED_LOW);
  234. // Test WHOAMI
  235. uint8_t whoami = _register_read(ADDR_WHO_AM_I);
  236. if (whoami != WHO_I_AM) {
  237. hal.console->printf("LSM303D: unexpected WHOAMI 0x%x\n", (unsigned)whoami);
  238. goto fail_whoami;
  239. }
  240. uint8_t tries;
  241. for (tries = 0; tries < 5; tries++) {
  242. // ensure the chip doesn't interpret any other bus traffic as I2C
  243. _disable_i2c();
  244. /* enable mag */
  245. _reg7_expected = REG7_CONT_MODE_M;
  246. _register_write(ADDR_CTRL_REG7, _reg7_expected);
  247. _register_write(ADDR_CTRL_REG5, REG5_RES_HIGH_M);
  248. // DRDY on MAG on INT2
  249. _register_write(ADDR_CTRL_REG4, 0x04);
  250. _mag_set_range(LSM303D_MAG_DEFAULT_RANGE_GA);
  251. _mag_set_samplerate(LSM303D_MAG_DEFAULT_RATE);
  252. hal.scheduler->delay(10);
  253. if (_data_ready()) {
  254. break;
  255. }
  256. }
  257. if (tries == 5) {
  258. hal.console->printf("Failed to boot LSM303D 5 times\n");
  259. goto fail_tries;
  260. }
  261. _dev->set_speed(AP_HAL::Device::SPEED_HIGH);
  262. _dev->get_semaphore()->give();
  263. return true;
  264. fail_tries:
  265. fail_whoami:
  266. _dev->get_semaphore()->give();
  267. _dev->set_speed(AP_HAL::Device::SPEED_HIGH);
  268. return false;
  269. }
  270. void AP_Compass_LSM303D::_update()
  271. {
  272. if (!_read_sample()) {
  273. return;
  274. }
  275. Vector3f raw_field = Vector3f(_mag_x, _mag_y, _mag_z) * _mag_range_scale;
  276. accumulate_sample(raw_field, _compass_instance, 10);
  277. }
  278. // Read Sensor data
  279. void AP_Compass_LSM303D::read()
  280. {
  281. if (!_initialised) {
  282. return;
  283. }
  284. drain_accumulated_samples(_compass_instance);
  285. }
  286. void AP_Compass_LSM303D::_disable_i2c()
  287. {
  288. // TODO: use the register names
  289. uint8_t a = _register_read(0x02);
  290. _register_write(0x02, (0x10 | a));
  291. a = _register_read(0x02);
  292. _register_write(0x02, (0xF7 & a));
  293. a = _register_read(0x15);
  294. _register_write(0x15, (0x80 | a));
  295. a = _register_read(0x02);
  296. _register_write(0x02, (0xE7 & a));
  297. }
  298. bool AP_Compass_LSM303D::_mag_set_range(uint8_t max_ga)
  299. {
  300. uint8_t setbits = 0;
  301. uint8_t clearbits = REG6_FULL_SCALE_BITS_M;
  302. float new_scale_ga_digit = 0.0f;
  303. if (max_ga == 0) {
  304. max_ga = 12;
  305. }
  306. if (max_ga <= 2) {
  307. _mag_range_ga = 2;
  308. setbits |= REG6_FULL_SCALE_2GA_M;
  309. new_scale_ga_digit = 0.080f;
  310. } else if (max_ga <= 4) {
  311. _mag_range_ga = 4;
  312. setbits |= REG6_FULL_SCALE_4GA_M;
  313. new_scale_ga_digit = 0.160f;
  314. } else if (max_ga <= 8) {
  315. _mag_range_ga = 8;
  316. setbits |= REG6_FULL_SCALE_8GA_M;
  317. new_scale_ga_digit = 0.320f;
  318. } else if (max_ga <= 12) {
  319. _mag_range_ga = 12;
  320. setbits |= REG6_FULL_SCALE_12GA_M;
  321. new_scale_ga_digit = 0.479f;
  322. } else {
  323. return false;
  324. }
  325. _mag_range_scale = new_scale_ga_digit;
  326. _register_modify(ADDR_CTRL_REG6, clearbits, setbits);
  327. return true;
  328. }
  329. bool AP_Compass_LSM303D::_mag_set_samplerate(uint16_t frequency)
  330. {
  331. uint8_t setbits = 0;
  332. uint8_t clearbits = REG5_RATE_BITS_M;
  333. if (frequency == 0) {
  334. frequency = 100;
  335. }
  336. if (frequency <= 25) {
  337. setbits |= REG5_RATE_25HZ_M;
  338. _mag_samplerate = 25;
  339. } else if (frequency <= 50) {
  340. setbits |= REG5_RATE_50HZ_M;
  341. _mag_samplerate = 50;
  342. } else if (frequency <= 100) {
  343. setbits |= REG5_RATE_100HZ_M;
  344. _mag_samplerate = 100;
  345. } else {
  346. return false;
  347. }
  348. _register_modify(ADDR_CTRL_REG5, clearbits, setbits);
  349. return true;
  350. }