AP_Compass_IST8310.cpp 6.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243
  1. /*
  2. * Copyright (C) 2016 Emlid Ltd. 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. * Driver by Georgii Staroselskii, Sep 2016
  18. */
  19. #include "AP_Compass_IST8310.h"
  20. #include <stdio.h>
  21. #include <utility>
  22. #include <AP_HAL/AP_HAL.h>
  23. #include <AP_HAL/utility/sparse-endian.h>
  24. #include <AP_Math/AP_Math.h>
  25. #define WAI_REG 0x0
  26. #define DEVICE_ID 0x10
  27. #define OUTPUT_X_L_REG 0x3
  28. #define OUTPUT_X_H_REG 0x4
  29. #define OUTPUT_Y_L_REG 0x5
  30. #define OUTPUT_Y_H_REG 0x6
  31. #define OUTPUT_Z_L_REG 0x7
  32. #define OUTPUT_Z_H_REG 0x8
  33. #define CNTL1_REG 0xA
  34. #define CNTL1_VAL_SINGLE_MEASUREMENT_MODE 0x1
  35. #define CNTL2_REG 0xB
  36. #define CNTL2_VAL_SRST 1
  37. #define AVGCNTL_REG 0x41
  38. #define AVGCNTL_VAL_XZ_0 (0)
  39. #define AVGCNTL_VAL_XZ_2 (1)
  40. #define AVGCNTL_VAL_XZ_4 (2)
  41. #define AVGCNTL_VAL_XZ_8 (3)
  42. #define AVGCNTL_VAL_XZ_16 (4)
  43. #define AVGCNTL_VAL_Y_0 (0 << 3)
  44. #define AVGCNTL_VAL_Y_2 (1 << 3)
  45. #define AVGCNTL_VAL_Y_4 (2 << 3)
  46. #define AVGCNTL_VAL_Y_8 (3 << 3)
  47. #define AVGCNTL_VAL_Y_16 (4 << 3)
  48. #define PDCNTL_REG 0x42
  49. #define PDCNTL_VAL_PULSE_DURATION_NORMAL 0xC0
  50. #define SAMPLING_PERIOD_USEC (10 * AP_USEC_PER_MSEC)
  51. /*
  52. * FSR:
  53. * x, y: +- 1600 µT
  54. * z: +- 2500 µT
  55. *
  56. * Resolution according to datasheet is 0.3µT/LSB
  57. */
  58. #define IST8310_RESOLUTION 0.3
  59. static const int16_t IST8310_MAX_VAL_XY = (1600 / IST8310_RESOLUTION) + 1;
  60. static const int16_t IST8310_MIN_VAL_XY = -IST8310_MAX_VAL_XY;
  61. static const int16_t IST8310_MAX_VAL_Z = (2500 / IST8310_RESOLUTION) + 1;
  62. static const int16_t IST8310_MIN_VAL_Z = -IST8310_MAX_VAL_Z;
  63. extern const AP_HAL::HAL &hal;
  64. AP_Compass_Backend *AP_Compass_IST8310::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
  65. bool force_external,
  66. enum Rotation rotation)
  67. {
  68. if (!dev) {
  69. return nullptr;
  70. }
  71. AP_Compass_IST8310 *sensor = new AP_Compass_IST8310(std::move(dev), force_external, rotation);
  72. if (!sensor || !sensor->init()) {
  73. delete sensor;
  74. return nullptr;
  75. }
  76. return sensor;
  77. }
  78. AP_Compass_IST8310::AP_Compass_IST8310(AP_HAL::OwnPtr<AP_HAL::Device> dev,
  79. bool force_external,
  80. enum Rotation rotation)
  81. : _dev(std::move(dev))
  82. , _rotation(rotation)
  83. , _force_external(force_external)
  84. {
  85. }
  86. bool AP_Compass_IST8310::init()
  87. {
  88. uint8_t reset_count = 0;
  89. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  90. return false;
  91. }
  92. // high retries for init
  93. _dev->set_retries(10);
  94. uint8_t whoami;
  95. if (!_dev->read_registers(WAI_REG, &whoami, 1) ||
  96. whoami != DEVICE_ID) {
  97. // not an IST8310
  98. goto fail;
  99. }
  100. for (; reset_count < 5; reset_count++) {
  101. if (!_dev->write_register(CNTL2_REG, CNTL2_VAL_SRST)) {
  102. hal.scheduler->delay(10);
  103. continue;
  104. }
  105. hal.scheduler->delay(10);
  106. uint8_t cntl2 = 0xFF;
  107. if (_dev->read_registers(CNTL2_REG, &cntl2, 1) &&
  108. (cntl2 & 0x01) == 0) {
  109. break;
  110. }
  111. }
  112. if (reset_count == 5) {
  113. printf("IST8310: failed to reset device\n");
  114. goto fail;
  115. }
  116. if (!_dev->write_register(AVGCNTL_REG, AVGCNTL_VAL_Y_16 | AVGCNTL_VAL_XZ_16) ||
  117. !_dev->write_register(PDCNTL_REG, PDCNTL_VAL_PULSE_DURATION_NORMAL)) {
  118. printf("IST8310: found device but could not set it up\n");
  119. goto fail;
  120. }
  121. // lower retries for run
  122. _dev->set_retries(3);
  123. // start state machine: request a sample
  124. start_conversion();
  125. _dev->get_semaphore()->give();
  126. _instance = register_compass();
  127. printf("%s found on bus %u id %u address 0x%02x\n", name,
  128. _dev->bus_num(), _dev->get_bus_id(), _dev->get_bus_address());
  129. set_rotation(_instance, _rotation);
  130. _dev->set_device_type(DEVTYPE_IST8310);
  131. set_dev_id(_instance, _dev->get_bus_id());
  132. if (_force_external) {
  133. set_external(_instance, true);
  134. }
  135. _periodic_handle = _dev->register_periodic_callback(SAMPLING_PERIOD_USEC,
  136. FUNCTOR_BIND_MEMBER(&AP_Compass_IST8310::timer, void));
  137. _perf_xfer_err = hal.util->perf_alloc(AP_HAL::Util::PC_COUNT, "IST8310_xfer_err");
  138. _perf_bad_data = hal.util->perf_alloc(AP_HAL::Util::PC_COUNT, "IST8310_bad_data");
  139. return true;
  140. fail:
  141. _dev->get_semaphore()->give();
  142. return false;
  143. }
  144. void AP_Compass_IST8310::start_conversion()
  145. {
  146. if (!_dev->write_register(CNTL1_REG, CNTL1_VAL_SINGLE_MEASUREMENT_MODE)) {
  147. hal.util->perf_count(_perf_xfer_err);
  148. _ignore_next_sample = true;
  149. }
  150. }
  151. void AP_Compass_IST8310::timer()
  152. {
  153. if (_ignore_next_sample) {
  154. _ignore_next_sample = false;
  155. start_conversion();
  156. return;
  157. }
  158. struct PACKED {
  159. le16_t rx;
  160. le16_t ry;
  161. le16_t rz;
  162. } buffer;
  163. bool ret = _dev->read_registers(OUTPUT_X_L_REG, (uint8_t *) &buffer, sizeof(buffer));
  164. if (!ret) {
  165. hal.util->perf_count(_perf_xfer_err);
  166. return;
  167. }
  168. start_conversion();
  169. /* same period, but start counting from now */
  170. _dev->adjust_periodic_callback(_periodic_handle, SAMPLING_PERIOD_USEC);
  171. auto x = static_cast<int16_t>(le16toh(buffer.rx));
  172. auto y = static_cast<int16_t>(le16toh(buffer.ry));
  173. auto z = static_cast<int16_t>(le16toh(buffer.rz));
  174. /*
  175. * Check if value makes sense according to the FSR and Resolution of
  176. * this sensor, discarding outliers
  177. */
  178. if (x > IST8310_MAX_VAL_XY || x < IST8310_MIN_VAL_XY ||
  179. y > IST8310_MAX_VAL_XY || y < IST8310_MIN_VAL_XY ||
  180. z > IST8310_MAX_VAL_Z || z < IST8310_MIN_VAL_Z) {
  181. hal.util->perf_count(_perf_bad_data);
  182. return;
  183. }
  184. // flip Z to conform to right-hand rule convention
  185. z = -z;
  186. /* Resolution: 0.3 µT/LSB - already convert to milligauss */
  187. Vector3f field = Vector3f{x * 3.0f, y * 3.0f, z * 3.0f};
  188. accumulate_sample(field, _instance);
  189. }
  190. void AP_Compass_IST8310::read()
  191. {
  192. drain_accumulated_samples(_instance);
  193. }