AP_Compass_IST8308.cpp 6.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230
  1. /*
  2. * Copyright (C) 2018 Lucas De Marchi. 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 2 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_IST8308.h"
  18. #include <stdio.h>
  19. #include <utility>
  20. #include <AP_HAL/AP_HAL.h>
  21. #include <AP_HAL/utility/sparse-endian.h>
  22. #include <AP_Math/AP_Math.h>
  23. #define WAI_REG 0x0
  24. #define DEVICE_ID 0x08
  25. #define STAT1_REG 0x10
  26. #define STAT1_VAL_DRDY 0x1
  27. #define STAT1_VAL_DOR 0x2
  28. #define DATAX_L_REG 0x11
  29. #define DATAX_H_REG 0x12
  30. #define DATAY_L_REG 0x13
  31. #define DATAY_H_REG 0x14
  32. #define DATAZ_L_REG 0x15
  33. #define DATAZ_H_REG 0x16
  34. #define CNTL1_REG 0x30
  35. #define CNTL2_REG 0x31
  36. #define CNTL2_VAL_STANDBY_MODE 0x0
  37. #define CNTL2_VAL_SINGLE_MODE 0x1
  38. #define CNTL2_VAL_CONT_ODR10_MODE 0x2
  39. #define CNTL2_VAL_CONT_ODR20_MODE 0x4
  40. #define CNTL2_VAL_CONT_ODR50_MODE 0x6
  41. #define CNTL2_VAL_CONT_ODR100_MODE 0x8
  42. #define CNTL2_VAL_CONT_ODR200_MODE 0xA
  43. #define CNTL2_VAL_CONT_ODR8_MODE 0xB
  44. #define CNTL2_VAL_CONT_ODR1_MODE 0xC
  45. #define CNTL2_VAL_CONT_ODR0P5_MODE 0xD
  46. #define CNTL2_VAL_SINGLE_TEST_MODE 0x10
  47. #define CNTL3_REG 0x32
  48. #define CNTL3_VAL_SRST 1
  49. #define CNTL3_VAL_DRDY_POLARITY_HIGH (1 << 2)
  50. #define CNTL3_VAL_DRDY_EN (1 << 3)
  51. #define CNTL4_REG 0x34
  52. #define CNTL4_VAL_DYNAMIC_RANGE_500 0
  53. #define CNTL4_VAL_DYNAMIC_RANGE_200 0x1
  54. #define OSRCNTL_REG 0x41
  55. #define OSRCNTL_VAL_XZ_1 (0)
  56. #define OSRCNTL_VAL_XZ_2 (1)
  57. #define OSRCNTL_VAL_XZ_4 (2)
  58. #define OSRCNTL_VAL_XZ_8 (3)
  59. #define OSRCNTL_VAL_XZ_16 (4)
  60. #define OSRCNTL_VAL_XZ_32 (4)
  61. #define OSRCNTL_VAL_Y_1 (0 << 3)
  62. #define OSRCNTL_VAL_Y_2 (1 << 3)
  63. #define OSRCNTL_VAL_Y_4 (2 << 3)
  64. #define OSRCNTL_VAL_Y_8 (3 << 3)
  65. #define OSRCNTL_VAL_Y_16 (4 << 3)
  66. #define OSRCNTL_VAL_Y_32 (5 << 3)
  67. #define SAMPLING_PERIOD_USEC (10 * AP_USEC_PER_MSEC)
  68. extern const AP_HAL::HAL &hal;
  69. AP_Compass_Backend *AP_Compass_IST8308::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
  70. bool force_external,
  71. enum Rotation rotation)
  72. {
  73. if (!dev) {
  74. return nullptr;
  75. }
  76. AP_Compass_IST8308 *sensor = new AP_Compass_IST8308(std::move(dev), force_external, rotation);
  77. if (!sensor || !sensor->init()) {
  78. delete sensor;
  79. return nullptr;
  80. }
  81. return sensor;
  82. }
  83. AP_Compass_IST8308::AP_Compass_IST8308(AP_HAL::OwnPtr<AP_HAL::Device> dev,
  84. bool force_external,
  85. enum Rotation rotation)
  86. : _dev(std::move(dev))
  87. , _rotation(rotation)
  88. , _force_external(force_external)
  89. {
  90. }
  91. bool AP_Compass_IST8308::init()
  92. {
  93. uint8_t reset_count = 0;
  94. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  95. return false;
  96. }
  97. // high retries for init
  98. _dev->set_retries(10);
  99. uint8_t whoami;
  100. if (!_dev->read_registers(WAI_REG, &whoami, 1) ||
  101. whoami != DEVICE_ID) {
  102. // not an IST8308
  103. goto fail;
  104. }
  105. for (; reset_count < 5; reset_count++) {
  106. if (!_dev->write_register(CNTL3_REG, CNTL3_VAL_SRST)) {
  107. hal.scheduler->delay(10);
  108. continue;
  109. }
  110. hal.scheduler->delay(20);
  111. uint8_t cntl3 = 0xFF;
  112. if (_dev->read_registers(CNTL3_REG, &cntl3, 1) &&
  113. (cntl3 & 0x01) == 0) {
  114. break;
  115. }
  116. }
  117. if (reset_count == 5) {
  118. printf("IST8308: failed to reset device\n");
  119. goto fail;
  120. }
  121. // DRDY enabled
  122. // Dynamic Range=±500 uT, Sensitivity=6.6 LSB/uT
  123. // OSR 16 (max 100Hz)
  124. // Start continuous mode at 100Hz
  125. if (!_dev->write_register(CNTL3_REG, CNTL3_VAL_DRDY_EN) ||
  126. !_dev->write_register(CNTL4_REG, CNTL4_VAL_DYNAMIC_RANGE_500) ||
  127. !_dev->write_register(OSRCNTL_REG, OSRCNTL_VAL_Y_16 | OSRCNTL_VAL_XZ_16) ||
  128. !_dev->write_register(CNTL2_REG, CNTL2_VAL_CONT_ODR100_MODE)) {
  129. printf("IST8308: found device but could not set it up\n");
  130. goto fail;
  131. }
  132. // lower retries for run
  133. _dev->set_retries(3);
  134. _dev->get_semaphore()->give();
  135. _instance = register_compass();
  136. printf("%s found on bus %u id %u address 0x%02x\n", name,
  137. _dev->bus_num(), _dev->get_bus_id(), _dev->get_bus_address());
  138. set_rotation(_instance, _rotation);
  139. _dev->set_device_type(DEVTYPE_IST8308);
  140. set_dev_id(_instance, _dev->get_bus_id());
  141. if (_force_external) {
  142. set_external(_instance, true);
  143. }
  144. _dev->register_periodic_callback(SAMPLING_PERIOD_USEC,
  145. FUNCTOR_BIND_MEMBER(&AP_Compass_IST8308::timer, void));
  146. _perf_xfer_err = hal.util->perf_alloc(AP_HAL::Util::PC_COUNT, "IST8308_xfer_err");
  147. return true;
  148. fail:
  149. _dev->get_semaphore()->give();
  150. return false;
  151. }
  152. void AP_Compass_IST8308::timer()
  153. {
  154. struct PACKED {
  155. le16_t rx;
  156. le16_t ry;
  157. le16_t rz;
  158. } buffer;
  159. uint8_t stat;
  160. if (!_dev->read_registers(STAT1_REG, &stat, 1) ||
  161. !(stat & STAT1_VAL_DRDY)) {
  162. hal.util->perf_count(_perf_xfer_err);
  163. return;
  164. }
  165. if (stat & STAT1_VAL_DOR) {
  166. printf("IST8308: data overrun\n");
  167. }
  168. if (!_dev->read_registers(DATAX_L_REG, (uint8_t *) &buffer,
  169. sizeof(buffer))) {
  170. hal.util->perf_count(_perf_xfer_err);
  171. return;
  172. }
  173. auto x = static_cast<int16_t>(le16toh(buffer.rx));
  174. auto y = static_cast<int16_t>(le16toh(buffer.ry));
  175. auto z = static_cast<int16_t>(le16toh(buffer.rz));
  176. // flip Z to conform to right-hand rule convention
  177. z = -z;
  178. /* Resolution: 0.1515 µT/LSB - already convert to milligauss */
  179. Vector3f field = Vector3f{x * 1.515f, y * 1.515f, z * 1.515f};
  180. accumulate_sample(field, _instance);
  181. }
  182. void AP_Compass_IST8308::read()
  183. {
  184. drain_accumulated_samples(_instance);
  185. }