APM:Libraries
AP_Compass_QMC5883L.cpp
Go to the documentation of this file.
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 
22 #include <stdio.h>
23 #include <utility>
24 
25 #include <AP_HAL/AP_HAL.h>
27 #include <AP_Math/AP_Math.h>
28 
29 #define QMC5883L_REG_CONF1 0x09
30 #define QMC5883L_REG_CONF2 0x0A
31 
32 // data output rates for 5883L
33 #define QMC5883L_ODR_10HZ (0x00 << 2)
34 #define QMC5883L_ODR_50HZ (0x01 << 2)
35 #define QMC5883L_ODR_100HZ (0x02 << 2)
36 #define QMC5883L_ODR_200HZ (0x03 << 2)
37 
38 // Sensor operation modes
39 #define QMC5883L_MODE_STANDBY 0x00
40 #define QMC5883L_MODE_CONTINUOUS 0x01
41 
42 #define QMC5883L_RNG_2G (0x00 << 4)
43 #define QMC5883L_RNG_8G (0x01 << 4)
44 
45 #define QMC5883L_OSR_512 (0x00 << 6)
46 #define QMC5883L_OSR_256 (0x01 << 6)
47 #define QMC5883L_OSR_128 (0x10 << 6)
48 #define QMC5883L_OSR_64 (0x11 << 6)
49 
50 #define QMC5883L_RST 0x80
51 
52 #define QMC5883L_REG_DATA_OUTPUT_X 0x00
53 #define QMC5883L_REG_STATUS 0x06
54 
55 #define QMC5883L_REG_ID 0x0D
56 #define QMC5883_ID_VAL 0xFF
57 
58 extern const AP_HAL::HAL &hal;
59 
62  bool force_external,
63  enum Rotation rotation)
64 {
65  if (!dev) {
66  return nullptr;
67  }
68 
69  AP_Compass_QMC5883L *sensor = new AP_Compass_QMC5883L(compass, std::move(dev),force_external,rotation);
70  if (!sensor || !sensor->init()) {
71  delete sensor;
72  return nullptr;
73  }
74 
75  return sensor;
76 }
77 
80  bool force_external,
81  enum Rotation rotation)
82  : AP_Compass_Backend(compass)
83  , _dev(std::move(dev))
84  , _rotation(rotation)
85  , _force_external(force_external)
86 {
87 }
88 
90 {
92  return false;
93  }
94 
95  _dev->set_retries(10);
96 
97 #if 0
99 #endif
100 
101  if(!_check_whoami()){
102  goto fail;
103  }
104 
105  if (!_dev->write_register(0x0B, 0x01)||
106  !_dev->write_register(0x20, 0x40)||
107  !_dev->write_register(0x21, 0x01)||
112  QMC5883L_RNG_8G)) {
113  goto fail;
114  }
115 
116  // lower retries for run
117  _dev->set_retries(3);
118 
119  _dev->get_semaphore()->give();
120 
122 
123  printf("%s found on bus %u id %u address 0x%02x\n", name,
125 
127 
130 
131  if (_force_external) {
132  set_external(_instance, true);
133  }
134 
135  //Enable 100HZ
138 
139  return true;
140 
141  fail:
142  _dev->get_semaphore()->give();
143  return false;
144 }
146 {
147  uint8_t whoami;
148  //Affected by other devices,must read registers 0x00 once or reset,after can read the ID registers reliably
149  _dev->read_registers(0x00,&whoami,1);
150  if (!_dev->read_registers(0x0C, &whoami,1)||
151  whoami != 0x01){
152  return false;
153  }
154  if (!_dev->read_registers(QMC5883L_REG_ID, &whoami,1)||
155  whoami != QMC5883_ID_VAL){
156  return false;
157  }
158  return true;
159 }
160 
162 {
163  struct PACKED {
164  le16_t rx;
165  le16_t ry;
166  le16_t rz;
167  } buffer;
168 
169  const float range_scale = 1000.0f / 3000.0f;
170 
171  uint8_t status;
172  if(!_dev->read_registers(QMC5883L_REG_STATUS,&status,1)){
173  return;
174  }
175  //new data is ready
176  if (!(status & 0x04)) {
177  return;
178  }
179 
180  if(!_dev->read_registers(QMC5883L_REG_DATA_OUTPUT_X, (uint8_t *) &buffer, sizeof(buffer))){
181  return ;
182  }
183 
184  auto x = -static_cast<int16_t>(le16toh(buffer.rx));
185  auto y = static_cast<int16_t>(le16toh(buffer.ry));
186  auto z = -static_cast<int16_t>(le16toh(buffer.rz));
187 
188 #if 0
189  printf("mag.x:%d\n",x);
190  printf("mag.y:%d\n",y);
191  printf("mag.z:%d\n",z);
192 #endif
193 
194  Vector3f field = Vector3f{x * range_scale , y * range_scale, z * range_scale };
195 
196  // rotate to the desired orientation
197  if (is_external(_instance)) {
198  field.rotate(ROTATION_YAW_90);
199  }
200 
201  /* rotate raw_field from sensor frame to body frame */
202  rotate_field(field, _instance);
203 
204  /* publish raw_field (uncorrected point sample) for calibration use */
206 
207  /* correct raw_field for known errors */
208  correct_field(field, _instance);
209 
210  if (!field_ok(field)) {
211  return;
212  }
213 
215  _accum += field;
216  _accum_count++;
217  if(_accum_count == 20){
218  _accum.x /= 2;
219  _accum.y /= 2;
220  _accum.z /= 2;
221  _accum_count = 10;
222  }
223  _sem->give();
224  }
225 }
226 
228 {
229  if (!_sem->take_nonblocking()) {
230  return;
231  }
232 
233  if (_accum_count == 0) {
234  _sem->give();
235  return;
236  }
237 
238  Vector3f field(_accum);
239  field /= _accum_count;
240 
242 
243  _accum.zero();
244  _accum_count = 0;
245 
246  _sem->give();
247 }
248 
250 {
251  printf("QMC5883L registers dump\n");
252  for (uint8_t reg = QMC5883L_REG_DATA_OUTPUT_X; reg <= 0x30; reg++) {
253  uint8_t v;
254  _dev->read_registers(reg,&v,1);
255  printf("%02x:%02x ", (unsigned)reg, (unsigned)v);
256  if ((reg - ( QMC5883L_REG_DATA_OUTPUT_X-1)) % 16 == 0) {
257  printf("\n");
258  }
259  }
260 }
261 
int printf(const char *fmt,...)
Definition: stdio.c:113
#define QMC5883_ID_VAL
#define QMC5883L_REG_CONF1
#define QMC5883L_OSR_512
void set_external(uint8_t instance, bool external)
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
#define QMC5883L_ODR_100HZ
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
uint32_t get_bus_id(void) const
Definition: Device.h:60
virtual AP_HAL::Semaphore * get_semaphore()=0
void rotate_field(Vector3f &mag, uint8_t instance)
virtual void set_retries(uint8_t retries)
Definition: Device.h:260
#define QMC5883L_REG_DATA_OUTPUT_X
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
void correct_field(Vector3f &mag, uint8_t i)
uint8_t get_bus_address(void) const
Definition: Device.h:65
bool field_ok(const Vector3f &field)
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
void set_dev_id(uint8_t instance, uint32_t dev_id)
Rotation
Definition: rotations.h:27
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, bool force_external, enum Rotation rotation=ROTATION_NONE)
uint8_t bus_num(void) const
Definition: Device.h:55
void fail(const char *why)
Definition: eedump.c:28
void set_device_type(uint8_t devtype)
Definition: Device.h:70
#define x(i)
virtual bool take_nonblocking() WARN_IF_UNUSED=0
AP_Compass_QMC5883L(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external, enum Rotation rotation)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
uint8_t register_compass(void) const
T y
Definition: vector3.h:67
#define QMC5883L_REG_ID
T z
Definition: vector3.h:67
virtual bool give()=0
float v
Definition: Printf.cpp:15
static Compass compass
Definition: AHRS_Test.cpp:20
uint16_t __ap_bitwise le16_t
Definition: sparse-endian.h:35
AP_HAL::Semaphore * _sem
AP_HAL::OwnPtr< AP_HAL::Device > _dev
void rotate(enum Rotation rotation)
Definition: vector3.cpp:28
#define QMC5883L_REG_STATUS
#define QMC5883L_MODE_CONTINUOUS
void set_rotation(uint8_t instance, enum Rotation rotation)
static constexpr const char * name
#define PACKED
Definition: AP_Common.h:28
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
bool is_external(uint8_t instance)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
void publish_raw_field(const Vector3f &mag, uint8_t instance)
static uint16_t le16toh(le16_t value)
Definition: sparse-endian.h:79
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
#define QMC5883L_RNG_8G
void zero()
Definition: vector3.h:182
T x
Definition: vector3.h:67
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14