AP_Compass_LIS3MDL.cpp 4.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169
  1. /*
  2. * This file is free software: you can redistribute it and/or modify it
  3. * under the terms of the GNU General Public License as published by the
  4. * Free Software Foundation, either version 3 of the License, or
  5. * (at your option) any later version.
  6. *
  7. * This file is distributed in the hope that it will be useful, but
  8. * WITHOUT ANY WARRANTY; without even the implied warranty of
  9. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  10. * See the GNU General Public License for more details.
  11. *
  12. * You should have received a copy of the GNU General Public License along
  13. * with this program. If not, see <http://www.gnu.org/licenses/>.
  14. */
  15. /*
  16. Driver by Andrew Tridgell, Nov 2016
  17. thanks to Robert Dickenson and the PX4 team for register definitions
  18. */
  19. #include "AP_Compass_LIS3MDL.h"
  20. #include <AP_HAL/AP_HAL.h>
  21. #include <utility>
  22. #include <AP_Math/AP_Math.h>
  23. #include <stdio.h>
  24. #define ADDR_CTRL_REG1 0x20
  25. #define ADDR_CTRL_REG2 0x21
  26. #define ADDR_CTRL_REG3 0x22
  27. #define ADDR_CTRL_REG4 0x23
  28. #define ADDR_CTRL_REG5 0x24
  29. #define ADDR_STATUS_REG 0x27
  30. #define ADDR_OUT_X_L 0x28
  31. #define ADDR_OUT_X_H 0x29
  32. #define ADDR_OUT_Y_L 0x2a
  33. #define ADDR_OUT_Y_H 0x2b
  34. #define ADDR_OUT_Z_L 0x2c
  35. #define ADDR_OUT_Z_H 0x2d
  36. #define ADDR_OUT_T_L 0x2e
  37. #define ADDR_OUT_T_H 0x2f
  38. #define MODE_REG_CONTINOUS_MODE (0 << 0)
  39. #define MODE_REG_SINGLE_MODE (1 << 0)
  40. #define ADDR_WHO_AM_I 0x0f
  41. #define ID_WHO_AM_I 0x3d
  42. extern const AP_HAL::HAL &hal;
  43. AP_Compass_Backend *AP_Compass_LIS3MDL::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
  44. bool force_external,
  45. enum Rotation rotation)
  46. {
  47. if (!dev) {
  48. return nullptr;
  49. }
  50. AP_Compass_LIS3MDL *sensor = new AP_Compass_LIS3MDL(std::move(dev), force_external, rotation);
  51. if (!sensor || !sensor->init()) {
  52. delete sensor;
  53. return nullptr;
  54. }
  55. return sensor;
  56. }
  57. AP_Compass_LIS3MDL::AP_Compass_LIS3MDL(AP_HAL::OwnPtr<AP_HAL::Device> _dev,
  58. bool _force_external,
  59. enum Rotation _rotation)
  60. : dev(std::move(_dev))
  61. , force_external(_force_external)
  62. , rotation(_rotation)
  63. {
  64. }
  65. bool AP_Compass_LIS3MDL::init()
  66. {
  67. if (!dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  68. return false;
  69. }
  70. if (dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
  71. dev->set_read_flag(0xC0);
  72. }
  73. // high retries for init
  74. dev->set_retries(10);
  75. uint8_t whoami;
  76. if (!dev->read_registers(ADDR_WHO_AM_I, &whoami, 1) ||
  77. whoami != ID_WHO_AM_I) {
  78. // not a 3MDL
  79. goto fail;
  80. }
  81. dev->setup_checked_registers(5);
  82. dev->write_register(ADDR_CTRL_REG1, 0xFC, true); // 80Hz, UHP
  83. dev->write_register(ADDR_CTRL_REG2, 0, true); // 4Ga range
  84. dev->write_register(ADDR_CTRL_REG3, 0, true); // continuous
  85. dev->write_register(ADDR_CTRL_REG4, 0x0C, true); // z-axis ultra high perf
  86. dev->write_register(ADDR_CTRL_REG5, 0x40, true); // block-data-update
  87. // lower retries for run
  88. dev->set_retries(3);
  89. dev->get_semaphore()->give();
  90. /* register the compass instance in the frontend */
  91. compass_instance = register_compass();
  92. printf("Found a LIS3MDL on 0x%x as compass %u\n", dev->get_bus_id(), compass_instance);
  93. set_rotation(compass_instance, rotation);
  94. if (force_external) {
  95. set_external(compass_instance, true);
  96. }
  97. dev->set_device_type(DEVTYPE_LIS3MDL);
  98. set_dev_id(compass_instance, dev->get_bus_id());
  99. // call timer() at 80Hz
  100. dev->register_periodic_callback(1000000U/80U,
  101. FUNCTOR_BIND_MEMBER(&AP_Compass_LIS3MDL::timer, void));
  102. return true;
  103. fail:
  104. dev->get_semaphore()->give();
  105. return false;
  106. }
  107. void AP_Compass_LIS3MDL::timer()
  108. {
  109. struct PACKED {
  110. int16_t magx;
  111. int16_t magy;
  112. int16_t magz;
  113. } data;
  114. const float range_scale = 1000.0f / 6842.0f;
  115. Vector3f field;
  116. // check data ready
  117. uint8_t status;
  118. if (!dev->read_registers(ADDR_STATUS_REG, (uint8_t *)&status, 1)) {
  119. goto check_registers;
  120. }
  121. if (!(status & 0x08)) {
  122. // data not available yet
  123. goto check_registers;
  124. }
  125. if (!dev->read_registers(ADDR_OUT_X_L, (uint8_t *)&data, sizeof(data))) {
  126. goto check_registers;
  127. }
  128. field(data.magx * range_scale, data.magy * range_scale, data.magz * range_scale);
  129. accumulate_sample(field, compass_instance);
  130. check_registers:
  131. dev->check_next_register();
  132. }
  133. void AP_Compass_LIS3MDL::read()
  134. {
  135. drain_accumulated_samples(compass_instance);
  136. }