CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Compass/AP_Compass_QMC5883L.cpp
Views: 1798
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
extern const AP_HAL::HAL &hal;
61
62
AP_Compass_Backend *AP_Compass_QMC5883L::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
63
bool force_external,
64
enum Rotation rotation)
65
{
66
if (!dev) {
67
return nullptr;
68
}
69
70
AP_Compass_QMC5883L *sensor = NEW_NOTHROW AP_Compass_QMC5883L(std::move(dev),force_external,rotation);
71
if (!sensor || !sensor->init()) {
72
delete sensor;
73
return nullptr;
74
}
75
76
return sensor;
77
}
78
79
AP_Compass_QMC5883L::AP_Compass_QMC5883L(AP_HAL::OwnPtr<AP_HAL::Device> dev,
80
bool force_external,
81
enum Rotation rotation)
82
: _dev(std::move(dev))
83
, _rotation(rotation)
84
, _force_external(force_external)
85
{
86
}
87
88
bool AP_Compass_QMC5883L::init()
89
{
90
_dev->get_semaphore()->take_blocking();
91
92
_dev->set_retries(10);
93
94
#if 0
95
_dump_registers();
96
#endif
97
98
if(!_check_whoami()){
99
goto fail;
100
}
101
102
if (!_dev->write_register(0x0B, 0x01)||
103
!_dev->write_register(0x20, 0x40)||
104
!_dev->write_register(0x21, 0x01)||
105
!_dev->write_register(QMC5883L_REG_CONF1,
106
QMC5883L_MODE_CONTINUOUS|
107
QMC5883L_ODR_100HZ|
108
QMC5883L_OSR_512|
109
QMC5883L_RNG_8G)) {
110
goto fail;
111
}
112
113
// lower retries for run
114
_dev->set_retries(3);
115
116
_dev->get_semaphore()->give();
117
118
//register compass instance
119
_dev->set_device_type(DEVTYPE_QMC5883L);
120
if (!register_compass(_dev->get_bus_id(), _instance)) {
121
return false;
122
}
123
set_dev_id(_instance, _dev->get_bus_id());
124
125
printf("%s found on bus %u id %u address 0x%02x\n", name,
126
_dev->bus_num(), unsigned(_dev->get_bus_id()), _dev->get_bus_address());
127
128
set_rotation(_instance, _rotation);
129
130
if (_force_external) {
131
set_external(_instance, true);
132
}
133
134
//Enable 100HZ
135
_dev->register_periodic_callback(10000,
136
FUNCTOR_BIND_MEMBER(&AP_Compass_QMC5883L::timer, void));
137
138
return true;
139
140
fail:
141
_dev->get_semaphore()->give();
142
return false;
143
}
144
bool AP_Compass_QMC5883L::_check_whoami()
145
{
146
uint8_t whoami;
147
//Affected by other devices,must read registers 0x00 once or reset,after can read the ID registers reliably
148
_dev->read_registers(0x00,&whoami,1);
149
if (!_dev->read_registers(0x0C, &whoami,1)||
150
whoami != 0x01){
151
return false;
152
}
153
if (!_dev->read_registers(QMC5883L_REG_ID, &whoami,1)||
154
whoami != QMC5883_ID_VAL){
155
return false;
156
}
157
return true;
158
}
159
160
void AP_Compass_QMC5883L::timer()
161
{
162
struct PACKED {
163
le16_t rx;
164
le16_t ry;
165
le16_t rz;
166
} buffer;
167
168
const float range_scale = 1000.0f / 3000.0f;
169
170
uint8_t status;
171
if(!_dev->read_registers(QMC5883L_REG_STATUS,&status,1)){
172
return;
173
}
174
//new data is ready
175
if (!(status & 0x04)) {
176
return;
177
}
178
179
if(!_dev->read_registers(QMC5883L_REG_DATA_OUTPUT_X, (uint8_t *) &buffer, sizeof(buffer))){
180
return ;
181
}
182
183
auto x = -static_cast<int16_t>(le16toh(buffer.rx));
184
auto y = static_cast<int16_t>(le16toh(buffer.ry));
185
auto z = -static_cast<int16_t>(le16toh(buffer.rz));
186
187
#if 0
188
printf("mag.x:%d\n",x);
189
printf("mag.y:%d\n",y);
190
printf("mag.z:%d\n",z);
191
#endif
192
193
Vector3f field = Vector3f{x * range_scale , y * range_scale, z * range_scale };
194
195
// rotate to the desired orientation
196
if (is_external(_instance)) {
197
field.rotate(ROTATION_YAW_90);
198
}
199
200
accumulate_sample(field, _instance, 20);
201
}
202
203
void AP_Compass_QMC5883L::read()
204
{
205
drain_accumulated_samples(_instance);
206
}
207
208
void AP_Compass_QMC5883L::_dump_registers()
209
{
210
printf("QMC5883L registers dump\n");
211
for (uint8_t reg = QMC5883L_REG_DATA_OUTPUT_X; reg <= 0x30; reg++) {
212
uint8_t v;
213
_dev->read_registers(reg,&v,1);
214
printf("%02x:%02x ", (unsigned)reg, (unsigned)v);
215
if ((reg - ( QMC5883L_REG_DATA_OUTPUT_X-1)) % 16 == 0) {
216
printf("\n");
217
}
218
}
219
}
220
221
#endif // AP_COMPASS_QMC5883L_ENABLED
222
223