AP_Compass_AK8963.cpp 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391
  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 <assert.h>
  14. #include <utility>
  15. #include <AP_Math/AP_Math.h>
  16. #include <AP_HAL/AP_HAL.h>
  17. #include "AP_Compass_AK8963.h"
  18. #include <AP_InertialSensor/AP_InertialSensor_Invensense.h>
  19. #define AK8963_I2C_ADDR 0x0c
  20. #define AK8963_WIA 0x00
  21. # define AK8963_Device_ID 0x48
  22. #define AK8963_HXL 0x03
  23. /* bit definitions for AK8963 CNTL1 */
  24. #define AK8963_CNTL1 0x0A
  25. # define AK8963_CONTINUOUS_MODE1 0x02
  26. # define AK8963_CONTINUOUS_MODE2 0x06
  27. # define AK8963_SELFTEST_MODE 0x08
  28. # define AK8963_POWERDOWN_MODE 0x00
  29. # define AK8963_FUSE_MODE 0x0f
  30. # define AK8963_16BIT_ADC 0x10
  31. # define AK8963_14BIT_ADC 0x00
  32. #define AK8963_CNTL2 0x0B
  33. # define AK8963_RESET 0x01
  34. #define AK8963_ASAX 0x10
  35. #define AK8963_MILLIGAUSS_SCALE 10.0f
  36. struct PACKED sample_regs {
  37. int16_t val[3];
  38. uint8_t st2;
  39. };
  40. extern const AP_HAL::HAL &hal;
  41. AP_Compass_AK8963::AP_Compass_AK8963(AP_AK8963_BusDriver *bus,
  42. enum Rotation rotation)
  43. : _bus(bus)
  44. , _rotation(rotation)
  45. {
  46. }
  47. AP_Compass_AK8963::~AP_Compass_AK8963()
  48. {
  49. delete _bus;
  50. }
  51. AP_Compass_Backend *AP_Compass_AK8963::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
  52. enum Rotation rotation)
  53. {
  54. if (!dev) {
  55. return nullptr;
  56. }
  57. AP_AK8963_BusDriver *bus = new AP_AK8963_BusDriver_HALDevice(std::move(dev));
  58. if (!bus) {
  59. return nullptr;
  60. }
  61. AP_Compass_AK8963 *sensor = new AP_Compass_AK8963(bus, rotation);
  62. if (!sensor || !sensor->init()) {
  63. delete sensor;
  64. return nullptr;
  65. }
  66. return sensor;
  67. }
  68. AP_Compass_Backend *AP_Compass_AK8963::probe_mpu9250(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
  69. enum Rotation rotation)
  70. {
  71. if (!dev) {
  72. return nullptr;
  73. }
  74. AP_InertialSensor &ins = *AP_InertialSensor::get_singleton();
  75. /* Allow MPU9250 to shortcut auxiliary bus and host bus */
  76. ins.detect_backends();
  77. return probe(std::move(dev), rotation);
  78. }
  79. AP_Compass_Backend *AP_Compass_AK8963::probe_mpu9250(uint8_t mpu9250_instance,
  80. enum Rotation rotation)
  81. {
  82. AP_InertialSensor &ins = *AP_InertialSensor::get_singleton();
  83. AP_AK8963_BusDriver *bus =
  84. new AP_AK8963_BusDriver_Auxiliary(ins, HAL_INS_MPU9250_SPI, mpu9250_instance, AK8963_I2C_ADDR);
  85. if (!bus) {
  86. return nullptr;
  87. }
  88. AP_Compass_AK8963 *sensor = new AP_Compass_AK8963(bus, rotation);
  89. if (!sensor || !sensor->init()) {
  90. delete sensor;
  91. return nullptr;
  92. }
  93. return sensor;
  94. }
  95. bool AP_Compass_AK8963::init()
  96. {
  97. AP_HAL::Semaphore *bus_sem = _bus->get_semaphore();
  98. if (!bus_sem || !_bus->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  99. hal.console->printf("AK8963: Unable to get bus semaphore\n");
  100. return false;
  101. }
  102. if (!_bus->configure()) {
  103. hal.console->printf("AK8963: Could not configure the bus\n");
  104. goto fail;
  105. }
  106. if (!_check_id()) {
  107. hal.console->printf("AK8963: Wrong id\n");
  108. goto fail;
  109. }
  110. if (!_calibrate()) {
  111. hal.console->printf("AK8963: Could not read calibration data\n");
  112. goto fail;
  113. }
  114. if (!_setup_mode()) {
  115. hal.console->printf("AK8963: Could not setup mode\n");
  116. goto fail;
  117. }
  118. if (!_bus->start_measurements()) {
  119. hal.console->printf("AK8963: Could not start measurements\n");
  120. goto fail;
  121. }
  122. _initialized = true;
  123. /* register the compass instance in the frontend */
  124. _compass_instance = register_compass();
  125. set_rotation(_compass_instance, _rotation);
  126. _bus->set_device_type(DEVTYPE_AK8963);
  127. set_dev_id(_compass_instance, _bus->get_bus_id());
  128. bus_sem->give();
  129. _bus->register_periodic_callback(10000, FUNCTOR_BIND_MEMBER(&AP_Compass_AK8963::_update, void));
  130. return true;
  131. fail:
  132. bus_sem->give();
  133. return false;
  134. }
  135. void AP_Compass_AK8963::read()
  136. {
  137. if (!_initialized) {
  138. return;
  139. }
  140. drain_accumulated_samples(_compass_instance);
  141. }
  142. void AP_Compass_AK8963::_make_adc_sensitivity_adjustment(Vector3f& field) const
  143. {
  144. static const float ADC_16BIT_RESOLUTION = 0.15f;
  145. field *= ADC_16BIT_RESOLUTION;
  146. }
  147. void AP_Compass_AK8963::_make_factory_sensitivity_adjustment(Vector3f& field) const
  148. {
  149. field.x *= _magnetometer_ASA[0];
  150. field.y *= _magnetometer_ASA[1];
  151. field.z *= _magnetometer_ASA[2];
  152. }
  153. void AP_Compass_AK8963::_update()
  154. {
  155. struct sample_regs regs;
  156. Vector3f raw_field;
  157. if (!_bus->block_read(AK8963_HXL, (uint8_t *) &regs, sizeof(regs))) {
  158. return;
  159. }
  160. /* Check for overflow. See AK8963's datasheet, section
  161. * 6.4.3.6 - Magnetic Sensor Overflow. */
  162. if ((regs.st2 & 0x08)) {
  163. return;
  164. }
  165. raw_field = Vector3f(regs.val[0], regs.val[1], regs.val[2]);
  166. if (is_zero(raw_field.x) && is_zero(raw_field.y) && is_zero(raw_field.z)) {
  167. return;
  168. }
  169. _make_factory_sensitivity_adjustment(raw_field);
  170. _make_adc_sensitivity_adjustment(raw_field);
  171. raw_field *= AK8963_MILLIGAUSS_SCALE;
  172. accumulate_sample(raw_field, _compass_instance, 10);
  173. }
  174. bool AP_Compass_AK8963::_check_id()
  175. {
  176. for (int i = 0; i < 5; i++) {
  177. uint8_t deviceid = 0;
  178. /* Read AK8963's id */
  179. if (_bus->register_read(AK8963_WIA, &deviceid) &&
  180. deviceid == AK8963_Device_ID) {
  181. return true;
  182. }
  183. }
  184. return false;
  185. }
  186. bool AP_Compass_AK8963::_setup_mode() {
  187. return _bus->register_write(AK8963_CNTL1, AK8963_CONTINUOUS_MODE2 | AK8963_16BIT_ADC);
  188. }
  189. bool AP_Compass_AK8963::_reset()
  190. {
  191. return _bus->register_write(AK8963_CNTL2, AK8963_RESET);
  192. }
  193. bool AP_Compass_AK8963::_calibrate()
  194. {
  195. /* Enable FUSE-mode in order to be able to read calibration data */
  196. _bus->register_write(AK8963_CNTL1, AK8963_FUSE_MODE | AK8963_16BIT_ADC);
  197. uint8_t response[3];
  198. _bus->block_read(AK8963_ASAX, response, 3);
  199. for (int i = 0; i < 3; i++) {
  200. float data = response[i];
  201. _magnetometer_ASA[i] = ((data - 128) / 256 + 1);
  202. }
  203. return true;
  204. }
  205. /* AP_HAL::I2CDevice implementation of the AK8963 */
  206. AP_AK8963_BusDriver_HALDevice::AP_AK8963_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
  207. : _dev(std::move(dev))
  208. {
  209. }
  210. bool AP_AK8963_BusDriver_HALDevice::block_read(uint8_t reg, uint8_t *buf, uint32_t size)
  211. {
  212. return _dev->read_registers(reg, buf, size);
  213. }
  214. bool AP_AK8963_BusDriver_HALDevice::register_read(uint8_t reg, uint8_t *val)
  215. {
  216. return _dev->read_registers(reg, val, 1);
  217. }
  218. bool AP_AK8963_BusDriver_HALDevice::register_write(uint8_t reg, uint8_t val)
  219. {
  220. return _dev->write_register(reg, val);
  221. }
  222. AP_HAL::Semaphore *AP_AK8963_BusDriver_HALDevice::get_semaphore()
  223. {
  224. return _dev->get_semaphore();
  225. }
  226. AP_HAL::Device::PeriodicHandle AP_AK8963_BusDriver_HALDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
  227. {
  228. return _dev->register_periodic_callback(period_usec, cb);
  229. }
  230. /* AK8963 on an auxiliary bus of IMU driver */
  231. AP_AK8963_BusDriver_Auxiliary::AP_AK8963_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,
  232. uint8_t backend_instance, uint8_t addr)
  233. {
  234. /*
  235. * Only initialize members. Fails are handled by configure or while
  236. * getting the semaphore
  237. */
  238. _bus = ins.get_auxiliary_bus(backend_id, backend_instance);
  239. if (!_bus) {
  240. return;
  241. }
  242. _slave = _bus->request_next_slave(addr);
  243. }
  244. AP_AK8963_BusDriver_Auxiliary::~AP_AK8963_BusDriver_Auxiliary()
  245. {
  246. /* After started it's owned by AuxiliaryBus */
  247. if (!_started) {
  248. delete _slave;
  249. }
  250. }
  251. bool AP_AK8963_BusDriver_Auxiliary::block_read(uint8_t reg, uint8_t *buf, uint32_t size)
  252. {
  253. if (_started) {
  254. /*
  255. * We can only read a block when reading the block of sample values -
  256. * calling with any other value is a mistake
  257. */
  258. assert(reg == AK8963_HXL);
  259. int n = _slave->read(buf);
  260. return n == static_cast<int>(size);
  261. }
  262. int r = _slave->passthrough_read(reg, buf, size);
  263. return r > 0 && static_cast<uint32_t>(r) == size;
  264. }
  265. bool AP_AK8963_BusDriver_Auxiliary::register_read(uint8_t reg, uint8_t *val)
  266. {
  267. return _slave->passthrough_read(reg, val, 1) == 1;
  268. }
  269. bool AP_AK8963_BusDriver_Auxiliary::register_write(uint8_t reg, uint8_t val)
  270. {
  271. return _slave->passthrough_write(reg, val) == 1;
  272. }
  273. AP_HAL::Semaphore *AP_AK8963_BusDriver_Auxiliary::get_semaphore()
  274. {
  275. return _bus ? _bus->get_semaphore() : nullptr;
  276. }
  277. bool AP_AK8963_BusDriver_Auxiliary::configure()
  278. {
  279. if (!_bus || !_slave) {
  280. return false;
  281. }
  282. return true;
  283. }
  284. bool AP_AK8963_BusDriver_Auxiliary::start_measurements()
  285. {
  286. if (_bus->register_periodic_read(_slave, AK8963_HXL, sizeof(sample_regs)) < 0) {
  287. return false;
  288. }
  289. _started = true;
  290. return true;
  291. }
  292. AP_HAL::Device::PeriodicHandle AP_AK8963_BusDriver_Auxiliary::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
  293. {
  294. return _bus->register_periodic_callback(period_usec, cb);
  295. }
  296. // set device type within a device class
  297. void AP_AK8963_BusDriver_Auxiliary::set_device_type(uint8_t devtype)
  298. {
  299. _bus->set_device_type(devtype);
  300. }
  301. // return 24 bit bus identifier
  302. uint32_t AP_AK8963_BusDriver_Auxiliary::get_bus_id(void) const
  303. {
  304. return _bus->get_bus_id();
  305. }