AP_Compass_LSM9DS1.cpp 5.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233
  1. #include <assert.h>
  2. #include <utility>
  3. #include <AP_Math/AP_Math.h>
  4. #include <AP_HAL/AP_HAL.h>
  5. #include "AP_Compass_LSM9DS1.h"
  6. #define LSM9DS1M_OFFSET_X_REG_L_M 0x05
  7. #define LSM9DS1M_OFFSET_X_REG_H_M 0x06
  8. #define LSM9DS1M_OFFSET_Y_REG_L_M 0x07
  9. #define LSM9DS1M_OFFSET_Y_REG_H_M 0x08
  10. #define LSM9DS1M_OFFSET_Z_REG_L_M 0x09
  11. #define LSM9DS1M_OFFSET_Z_REG_H_M 0x0A
  12. #define LSM9DS1M_WHO_AM_I 0x0F
  13. #define WHO_AM_I_MAG 0x3D
  14. #define LSM9DS1M_CTRL_REG1_M 0x20
  15. #define LSM9DS1M_TEMP_COMP (0x1 << 7)
  16. #define LSM9DS1M_XY_ULTRA_HIGH (0x3 << 5)
  17. #define LSM9DS1M_80HZ (0x7 << 2)
  18. #define LSM9DS1M_FAST_ODR (0x1 << 1)
  19. #define LSM9DS1M_CTRL_REG2_M 0x21
  20. #define LSM9DS1M_FS_16G (0x3 << 5)
  21. #define LSM9DS1M_CTRL_REG3_M 0x22
  22. #define LSM9DS1M_SPI_ENABLE (0x01 << 2)
  23. #define LSM9DS1M_CONTINUOUS_MODE 0x0
  24. #define LSM9DS1M_CTRL_REG4_M 0x23
  25. #define LSM9DS1M_Z_ULTRA_HIGH (0x3 << 2)
  26. #define LSM9DS1M_CTRL_REG5_M 0x24
  27. #define LSM9DS1M_BDU (0x0 << 6)
  28. #define LSM9DS1M_STATUS_REG_M 0x27
  29. #define LSM9DS1M_OUT_X_L_M 0x28
  30. #define LSM9DS1M_OUT_X_H_M 0x29
  31. #define LSM9DS1M_OUT_Y_L_M 0x2A
  32. #define LSM9DS1M_OUT_Y_H_M 0x2B
  33. #define LSM9DS1M_OUT_Z_L_M 0x2C
  34. #define LSM9DS1M_OUT_Z_H_M 0x2D
  35. #define LSM9DS1M_INT_CFG_M 0x30
  36. #define LSM9DS1M_INT_SRC_M 0x31
  37. #define LSM9DS1M_INT_THS_L_M 0x32
  38. #define LSM9DS1M_INT_THS_H_M 0x33
  39. struct PACKED sample_regs {
  40. uint8_t status;
  41. int16_t val[3];
  42. };
  43. extern const AP_HAL::HAL &hal;
  44. AP_Compass_LSM9DS1::AP_Compass_LSM9DS1(AP_HAL::OwnPtr<AP_HAL::Device> dev,
  45. enum Rotation rotation)
  46. : _dev(std::move(dev))
  47. , _rotation(rotation)
  48. {
  49. }
  50. AP_Compass_Backend *AP_Compass_LSM9DS1::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
  51. enum Rotation rotation)
  52. {
  53. if (!dev) {
  54. return nullptr;
  55. }
  56. AP_Compass_LSM9DS1 *sensor = new AP_Compass_LSM9DS1(std::move(dev), rotation);
  57. if (!sensor || !sensor->init()) {
  58. delete sensor;
  59. return nullptr;
  60. }
  61. return sensor;
  62. }
  63. bool AP_Compass_LSM9DS1::init()
  64. {
  65. AP_HAL::Semaphore *bus_sem = _dev->get_semaphore();
  66. if (!bus_sem || !bus_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  67. hal.console->printf("LSM9DS1: Unable to get bus semaphore\n");
  68. return false;
  69. }
  70. if (!_check_id()) {
  71. hal.console->printf("LSM9DS1: Could not check id\n");
  72. goto errout;
  73. }
  74. if (!_configure()) {
  75. hal.console->printf("LSM9DS1: Could not check id\n");
  76. goto errout;
  77. }
  78. if (!_set_scale()) {
  79. hal.console->printf("LSM9DS1: Could not set scale\n");
  80. goto errout;
  81. }
  82. _compass_instance = register_compass();
  83. set_rotation(_compass_instance, _rotation);
  84. _dev->set_device_type(DEVTYPE_LSM9DS1);
  85. set_dev_id(_compass_instance, _dev->get_bus_id());
  86. _dev->register_periodic_callback(10000, FUNCTOR_BIND_MEMBER(&AP_Compass_LSM9DS1::_update, void));
  87. bus_sem->give();
  88. return true;
  89. errout:
  90. bus_sem->give();
  91. return false;
  92. }
  93. void AP_Compass_LSM9DS1::_dump_registers()
  94. {
  95. hal.console->printf("LSMDS1 registers\n");
  96. for (uint8_t reg = LSM9DS1M_OFFSET_X_REG_L_M; reg <= LSM9DS1M_INT_THS_H_M; reg++) {
  97. uint8_t v = _register_read(reg);
  98. hal.console->printf("%02x:%02x ", (unsigned)reg, (unsigned)v);
  99. if ((reg - (LSM9DS1M_OFFSET_X_REG_L_M-1)) % 16 == 0) {
  100. hal.console->printf("\n");
  101. }
  102. }
  103. hal.console->printf("\n");
  104. }
  105. void AP_Compass_LSM9DS1::_update(void)
  106. {
  107. struct sample_regs regs;
  108. Vector3f raw_field;
  109. if (!_block_read(LSM9DS1M_STATUS_REG_M, (uint8_t *) &regs, sizeof(regs))) {
  110. return;
  111. }
  112. if (regs.status & 0x80) {
  113. return;
  114. }
  115. raw_field = Vector3f(regs.val[0], regs.val[1], regs.val[2]);
  116. if (is_zero(raw_field.x) && is_zero(raw_field.y) && is_zero(raw_field.z)) {
  117. return;
  118. }
  119. raw_field *= _scaling;
  120. accumulate_sample(raw_field, _compass_instance);
  121. }
  122. void AP_Compass_LSM9DS1::read()
  123. {
  124. drain_accumulated_samples(_compass_instance);
  125. }
  126. bool AP_Compass_LSM9DS1::_check_id(void)
  127. {
  128. // initially run the bus at low speed
  129. _dev->set_speed(AP_HAL::Device::SPEED_LOW);
  130. uint8_t value = _register_read(LSM9DS1M_WHO_AM_I);
  131. if (value != WHO_AM_I_MAG) {
  132. hal.console->printf("LSM9DS1: unexpected WHOAMI 0x%x\n", (unsigned)value);
  133. return false;
  134. }
  135. _dev->set_speed(AP_HAL::Device::SPEED_HIGH);
  136. return true;
  137. }
  138. bool AP_Compass_LSM9DS1::_configure(void)
  139. {
  140. _register_write(LSM9DS1M_CTRL_REG1_M, LSM9DS1M_TEMP_COMP | LSM9DS1M_XY_ULTRA_HIGH | LSM9DS1M_80HZ | LSM9DS1M_FAST_ODR);
  141. _register_write(LSM9DS1M_CTRL_REG2_M, LSM9DS1M_FS_16G);
  142. _register_write(LSM9DS1M_CTRL_REG3_M, LSM9DS1M_CONTINUOUS_MODE);
  143. _register_write(LSM9DS1M_CTRL_REG4_M, LSM9DS1M_Z_ULTRA_HIGH);
  144. _register_write(LSM9DS1M_CTRL_REG5_M, LSM9DS1M_BDU);
  145. return true;
  146. }
  147. bool AP_Compass_LSM9DS1::_set_scale(void)
  148. {
  149. static const uint8_t FS_M_MASK = 0xc;
  150. _register_modify(LSM9DS1M_CTRL_REG2_M, FS_M_MASK, LSM9DS1M_FS_16G);
  151. _scaling = 0.58f;
  152. return true;
  153. }
  154. uint8_t AP_Compass_LSM9DS1::_register_read(uint8_t reg)
  155. {
  156. uint8_t val = 0;
  157. /* set READ bit */
  158. reg |= 0x80;
  159. _dev->read_registers(reg, &val, 1);
  160. return val;
  161. }
  162. bool AP_Compass_LSM9DS1::_block_read(uint8_t reg, uint8_t *buf, uint32_t size)
  163. {
  164. /* set !MS bit */
  165. reg |= 0xc0;
  166. return _dev->read_registers(reg, buf, size);
  167. }
  168. void AP_Compass_LSM9DS1::_register_write(uint8_t reg, uint8_t val)
  169. {
  170. _dev->write_register(reg, val);
  171. }
  172. void AP_Compass_LSM9DS1::_register_modify(uint8_t reg, uint8_t clearbits, uint8_t setbits)
  173. {
  174. uint8_t val;
  175. val = _register_read(reg);
  176. val &= ~clearbits;
  177. val |= setbits;
  178. _register_write(reg, val);
  179. }