AP_Compass_QMC5883L.cpp 5.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218
  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 RadioLink LjWang, Jun 2017
  18. * GPS compass module See<http://www.radiolink.com>
  19. */
  20. #include "AP_Compass_QMC5883L.h"
  21. #include <stdio.h>
  22. #include <utility>
  23. #include <AP_HAL/AP_HAL.h>
  24. #include <AP_HAL/utility/sparse-endian.h>
  25. #include <AP_Math/AP_Math.h>
  26. #define QMC5883L_REG_CONF1 0x09
  27. #define QMC5883L_REG_CONF2 0x0A
  28. // data output rates for 5883L
  29. #define QMC5883L_ODR_10HZ (0x00 << 2)
  30. #define QMC5883L_ODR_50HZ (0x01 << 2)
  31. #define QMC5883L_ODR_100HZ (0x02 << 2)
  32. #define QMC5883L_ODR_200HZ (0x03 << 2)
  33. // Sensor operation modes
  34. #define QMC5883L_MODE_STANDBY 0x00
  35. #define QMC5883L_MODE_CONTINUOUS 0x01
  36. #define QMC5883L_RNG_2G (0x00 << 4)
  37. #define QMC5883L_RNG_8G (0x01 << 4)
  38. #define QMC5883L_OSR_512 (0x00 << 6)
  39. #define QMC5883L_OSR_256 (0x01 << 6)
  40. #define QMC5883L_OSR_128 (0x10 << 6)
  41. #define QMC5883L_OSR_64 (0x11 << 6)
  42. #define QMC5883L_RST 0x80
  43. #define QMC5883L_REG_DATA_OUTPUT_X 0x00
  44. #define QMC5883L_REG_STATUS 0x06
  45. #define QMC5883L_REG_ID 0x0D
  46. #define QMC5883_ID_VAL 0xFF
  47. extern const AP_HAL::HAL &hal;
  48. AP_Compass_Backend *AP_Compass_QMC5883L::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
  49. bool force_external,
  50. enum Rotation rotation)
  51. {
  52. if (!dev) {
  53. return nullptr;
  54. }
  55. AP_Compass_QMC5883L *sensor = new AP_Compass_QMC5883L(std::move(dev),force_external,rotation);
  56. if (!sensor || !sensor->init()) {
  57. delete sensor;
  58. return nullptr;
  59. }
  60. return sensor;
  61. }
  62. AP_Compass_QMC5883L::AP_Compass_QMC5883L(AP_HAL::OwnPtr<AP_HAL::Device> dev,
  63. bool force_external,
  64. enum Rotation rotation)
  65. : _dev(std::move(dev))
  66. , _rotation(rotation)
  67. , _force_external(force_external)
  68. {
  69. }
  70. bool AP_Compass_QMC5883L::init()
  71. {
  72. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  73. return false;
  74. }
  75. _dev->set_retries(10);
  76. #if 0
  77. _dump_registers();
  78. #endif
  79. if(!_check_whoami()){
  80. goto fail;
  81. }
  82. if (!_dev->write_register(0x0B, 0x01)||
  83. !_dev->write_register(0x20, 0x40)||
  84. !_dev->write_register(0x21, 0x01)||
  85. !_dev->write_register(QMC5883L_REG_CONF1,
  86. QMC5883L_MODE_CONTINUOUS|
  87. QMC5883L_ODR_100HZ|
  88. QMC5883L_OSR_512|
  89. QMC5883L_RNG_8G)) {
  90. goto fail;
  91. }
  92. // lower retries for run
  93. _dev->set_retries(3);
  94. _dev->get_semaphore()->give();
  95. _instance = register_compass();
  96. printf("%s found on bus %u id %u address 0x%02x\n", name,
  97. _dev->bus_num(), _dev->get_bus_id(), _dev->get_bus_address());
  98. set_rotation(_instance, _rotation);
  99. _dev->set_device_type(DEVTYPE_QMC5883L);
  100. set_dev_id(_instance, _dev->get_bus_id());
  101. if (_force_external) {
  102. set_external(_instance, true);
  103. }
  104. //Enable 100HZ
  105. _dev->register_periodic_callback(10000,
  106. FUNCTOR_BIND_MEMBER(&AP_Compass_QMC5883L::timer, void));
  107. return true;
  108. fail:
  109. _dev->get_semaphore()->give();
  110. return false;
  111. }
  112. bool AP_Compass_QMC5883L::_check_whoami()
  113. {
  114. uint8_t whoami;
  115. //Affected by other devices,must read registers 0x00 once or reset,after can read the ID registers reliably
  116. _dev->read_registers(0x00,&whoami,1);
  117. if (!_dev->read_registers(0x0C, &whoami,1)||
  118. whoami != 0x01){
  119. return false;
  120. }
  121. if (!_dev->read_registers(QMC5883L_REG_ID, &whoami,1)||
  122. whoami != QMC5883_ID_VAL){
  123. return false;
  124. }
  125. return true;
  126. }
  127. void AP_Compass_QMC5883L::timer()
  128. {
  129. struct PACKED {
  130. le16_t rx;
  131. le16_t ry;
  132. le16_t rz;
  133. } buffer;
  134. const float range_scale = 1000.0f / 3000.0f;
  135. uint8_t status;
  136. if(!_dev->read_registers(QMC5883L_REG_STATUS,&status,1)){
  137. return;
  138. }
  139. //new data is ready
  140. if (!(status & 0x04)) {
  141. return;
  142. }
  143. if(!_dev->read_registers(QMC5883L_REG_DATA_OUTPUT_X, (uint8_t *) &buffer, sizeof(buffer))){
  144. return ;
  145. }
  146. auto x = -static_cast<int16_t>(le16toh(buffer.rx));
  147. auto y = static_cast<int16_t>(le16toh(buffer.ry));
  148. auto z = -static_cast<int16_t>(le16toh(buffer.rz));
  149. #if 0
  150. printf("mag.x:%d\n",x);
  151. printf("mag.y:%d\n",y);
  152. printf("mag.z:%d\n",z);
  153. #endif
  154. Vector3f field = Vector3f{x * range_scale , y * range_scale, z * range_scale };
  155. // rotate to the desired orientation
  156. if (is_external(_instance)) {
  157. field.rotate(ROTATION_YAW_90);
  158. }
  159. accumulate_sample(field, _instance, 20);
  160. }
  161. void AP_Compass_QMC5883L::read()
  162. {
  163. drain_accumulated_samples(_instance);
  164. }
  165. void AP_Compass_QMC5883L::_dump_registers()
  166. {
  167. printf("QMC5883L registers dump\n");
  168. for (uint8_t reg = QMC5883L_REG_DATA_OUTPUT_X; reg <= 0x30; reg++) {
  169. uint8_t v;
  170. _dev->read_registers(reg,&v,1);
  171. printf("%02x:%02x ", (unsigned)reg, (unsigned)v);
  172. if ((reg - ( QMC5883L_REG_DATA_OUTPUT_X-1)) % 16 == 0) {
  173. printf("\n");
  174. }
  175. }
  176. }