Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Compass/AP_Compass_QMC5883L.cpp
9420 views
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
#if AP_COMPASS_QMC5883L_ENABLED
23
24
#include <stdio.h>
25
#include <utility>
26
27
#include <AP_HAL/AP_HAL.h>
28
#include <AP_HAL/utility/sparse-endian.h>
29
#include <AP_Math/AP_Math.h>
30
31
#define QMC5883L_REG_CONF1 0x09
32
#define QMC5883L_REG_CONF2 0x0A
33
34
// data output rates for 5883L
35
#define QMC5883L_ODR_10HZ (0x00 << 2)
36
#define QMC5883L_ODR_50HZ (0x01 << 2)
37
#define QMC5883L_ODR_100HZ (0x02 << 2)
38
#define QMC5883L_ODR_200HZ (0x03 << 2)
39
40
// Sensor operation modes
41
#define QMC5883L_MODE_STANDBY 0x00
42
#define QMC5883L_MODE_CONTINUOUS 0x01
43
44
#define QMC5883L_RNG_2G (0x00 << 4)
45
#define QMC5883L_RNG_8G (0x01 << 4)
46
47
#define QMC5883L_OSR_512 (0x00 << 6)
48
#define QMC5883L_OSR_256 (0x01 << 6)
49
#define QMC5883L_OSR_128 (0x10 << 6)
50
#define QMC5883L_OSR_64 (0x11 << 6)
51
52
#define QMC5883L_RST 0x80
53
54
#define QMC5883L_REG_DATA_OUTPUT_X 0x00
55
#define QMC5883L_REG_STATUS 0x06
56
57
#define QMC5883L_REG_ID 0x0D
58
#define QMC5883_ID_VAL 0xFF
59
60
AP_Compass_Backend *AP_Compass_QMC5883L::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
61
bool force_external,
62
enum Rotation rotation)
63
{
64
if (!dev) {
65
return nullptr;
66
}
67
68
AP_Compass_QMC5883L *sensor = NEW_NOTHROW AP_Compass_QMC5883L(std::move(dev),force_external,rotation);
69
if (!sensor || !sensor->init()) {
70
delete sensor;
71
return nullptr;
72
}
73
74
return sensor;
75
}
76
77
AP_Compass_QMC5883L::AP_Compass_QMC5883L(AP_HAL::OwnPtr<AP_HAL::Device> dev,
78
bool force_external,
79
enum Rotation rotation)
80
: _dev(std::move(dev))
81
, _rotation(rotation)
82
, _force_external(force_external)
83
{
84
}
85
86
bool AP_Compass_QMC5883L::init()
87
{
88
_dev->get_semaphore()->take_blocking();
89
90
_dev->set_retries(10);
91
92
#if 0
93
_dump_registers();
94
#endif
95
96
if(!_check_whoami()){
97
goto fail;
98
}
99
100
if (!_dev->write_register(0x0B, 0x01)||
101
!_dev->write_register(0x20, 0x40)||
102
!_dev->write_register(0x21, 0x01)||
103
!_dev->write_register(QMC5883L_REG_CONF1,
104
QMC5883L_MODE_CONTINUOUS|
105
QMC5883L_ODR_100HZ|
106
QMC5883L_OSR_512|
107
QMC5883L_RNG_8G)) {
108
goto fail;
109
}
110
111
// lower retries for run
112
_dev->set_retries(3);
113
114
_dev->get_semaphore()->give();
115
116
//register compass instance
117
_dev->set_device_type(DEVTYPE_QMC5883L);
118
if (!register_compass(_dev->get_bus_id())) {
119
return false;
120
}
121
122
printf("%s found on bus %u id %u address 0x%02x\n", name,
123
_dev->bus_num(), unsigned(_dev->get_bus_id()), _dev->get_bus_address());
124
125
set_rotation(_rotation);
126
127
if (_force_external) {
128
set_external(true);
129
}
130
131
//Enable 100HZ
132
_dev->register_periodic_callback(10000,
133
FUNCTOR_BIND_MEMBER(&AP_Compass_QMC5883L::timer, void));
134
135
return true;
136
137
fail:
138
_dev->get_semaphore()->give();
139
return false;
140
}
141
bool AP_Compass_QMC5883L::_check_whoami()
142
{
143
uint8_t whoami;
144
//Affected by other devices,must read registers 0x00 once or reset,after can read the ID registers reliably
145
_dev->read_registers(0x00,&whoami,1);
146
if (!_dev->read_registers(0x0C, &whoami,1)||
147
whoami != 0x01){
148
return false;
149
}
150
if (!_dev->read_registers(QMC5883L_REG_ID, &whoami,1)||
151
whoami != QMC5883_ID_VAL){
152
return false;
153
}
154
return true;
155
}
156
157
void AP_Compass_QMC5883L::timer()
158
{
159
struct PACKED {
160
le16_t rx;
161
le16_t ry;
162
le16_t rz;
163
} buffer;
164
165
const float range_scale = 1000.0f / 3000.0f;
166
167
uint8_t status;
168
if(!_dev->read_registers(QMC5883L_REG_STATUS,&status,1)){
169
return;
170
}
171
//new data is ready
172
if (!(status & 0x04)) {
173
return;
174
}
175
176
if(!_dev->read_registers(QMC5883L_REG_DATA_OUTPUT_X, (uint8_t *) &buffer, sizeof(buffer))){
177
return ;
178
}
179
180
auto x = -static_cast<int16_t>(le16toh(buffer.rx));
181
auto y = static_cast<int16_t>(le16toh(buffer.ry));
182
auto z = -static_cast<int16_t>(le16toh(buffer.rz));
183
184
#if 0
185
printf("mag.x:%d\n",x);
186
printf("mag.y:%d\n",y);
187
printf("mag.z:%d\n",z);
188
#endif
189
190
Vector3f field = Vector3f{x * range_scale , y * range_scale, z * range_scale };
191
192
// rotate to the desired orientation
193
if (is_external()) {
194
field.rotate(ROTATION_YAW_90);
195
}
196
197
accumulate_sample(field, 20);
198
}
199
200
void AP_Compass_QMC5883L::read()
201
{
202
drain_accumulated_samples();
203
}
204
205
void AP_Compass_QMC5883L::_dump_registers()
206
{
207
printf("QMC5883L registers dump\n");
208
for (uint8_t reg = QMC5883L_REG_DATA_OUTPUT_X; reg <= 0x30; reg++) {
209
uint8_t v;
210
_dev->read_registers(reg,&v,1);
211
printf("%02x:%02x ", (unsigned)reg, (unsigned)v);
212
if ((reg - ( QMC5883L_REG_DATA_OUTPUT_X-1)) % 16 == 0) {
213
printf("\n");
214
}
215
}
216
}
217
218
#endif // AP_COMPASS_QMC5883L_ENABLED
219
220