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_QMC5883P.cpp
Views: 1798
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
* Driver by Lokesh Ramina, Jan 2022
16
*/
17
#include "AP_Compass_QMC5883P.h"
18
19
#include <stdio.h>
20
21
#include <AP_HAL/AP_HAL.h>
22
#include <AP_Math/AP_Math.h>
23
24
#if AP_COMPASS_QMC5883P_ENABLED
25
26
//Register Address
27
#define QMC5883P_REG_ID 0x00
28
#define QMC5883P_REG_DATA_OUTPUT_X 0x01
29
#define QMC5883P_REG_DATA_OUTPUT_Z_MSB 0x06
30
#define QMC5883P_REG_STATUS 0x09
31
#define QMC5883P_REG_CONF1 0x0A
32
#define QMC5883P_REG_CONF2 0x0B
33
34
#define QMC5883P_ID_VAL 0x80
35
36
//Register values
37
// Sensor operation modes
38
#define QMC5883P_MODE_SUSPEND 0x00
39
#define QMC5883P_MODE_NORMAL 0x01
40
#define QMC5883P_MODE_SINGLE 0x02
41
#define QMC5883P_MODE_CONTINUOUS 0x03
42
43
// ODR data output rates for 5883L
44
#define QMC5883P_ODR_10HZ (0x00 << 2)
45
#define QMC5883P_ODR_50HZ (0x01 << 2)
46
#define QMC5883P_ODR_100HZ (0x02 << 2)
47
#define QMC5883P_ODR_200HZ (0x03 << 2)
48
49
// Over sampling Ratio OSR1
50
#define QMC5883P_OSR1_8 (0x00 << 4)
51
#define QMC5883P_OSR1_4 (0x01 << 4)
52
#define QMC5883P_OSR1_2 (0x02 << 4)
53
#define QMC5883P_OSR1_1 (0x03 << 4)
54
55
// Down sampling Rate OSR2
56
#define QMC5883P_OSR2_8 0x08
57
58
//RNG
59
#define QMC5883P_RNG_30G (0x00 << 2)
60
#define QMC5883P_RNG_12G (0x01 << 2)
61
#define QMC5883P_RNG_8G (0x10 << 2)
62
#define QMC5883P_RNG_2G (0x11 << 2)
63
64
#define QMC5883P_SET_XYZ_SIGN 0x29
65
66
//Reset
67
#define QMC5883P_RST 0x80
68
69
//Status Val
70
#define QMC5883P_STATUS_DATA_READY 0x01
71
72
#ifndef DEBUG
73
#define DEBUG 0
74
#endif
75
76
extern const AP_HAL::HAL &hal;
77
78
AP_Compass_Backend *AP_Compass_QMC5883P::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
79
bool force_external,
80
enum Rotation rotation)
81
{
82
if (!dev) {
83
return nullptr;
84
}
85
AP_Compass_QMC5883P *sensor = NEW_NOTHROW AP_Compass_QMC5883P(std::move(dev),force_external,rotation);
86
if (!sensor || !sensor->init()) {
87
delete sensor;
88
return nullptr;
89
}
90
return sensor;
91
}
92
93
AP_Compass_QMC5883P::AP_Compass_QMC5883P(AP_HAL::OwnPtr<AP_HAL::Device> dev,
94
bool force_external,
95
enum Rotation rotation)
96
: _dev(std::move(dev))
97
, _rotation(rotation)
98
, _force_external(force_external)
99
{
100
}
101
102
bool AP_Compass_QMC5883P::init()
103
{
104
_dev->get_semaphore()->take_blocking();
105
106
_dev->set_retries(10);
107
#if DEBUG
108
_dump_registers();
109
#endif
110
if (!_check_whoami()) {
111
goto fail;
112
}
113
//As mentioned in the Datasheet 7.2 to do continues mode 0x29 will set sign for X,Y,Z
114
if (!_dev->write_register(QMC5883P_REG_DATA_OUTPUT_Z_MSB, QMC5883P_SET_XYZ_SIGN)||
115
!_dev->write_register(QMC5883P_REG_CONF1,
116
QMC5883P_MODE_CONTINUOUS|
117
QMC5883P_ODR_100HZ|
118
QMC5883P_OSR1_8|
119
QMC5883P_OSR2_8)||
120
!_dev->write_register(QMC5883P_REG_CONF2,QMC5883P_OSR2_8)) {
121
goto fail;
122
}
123
124
// lower retries for run
125
_dev->set_retries(3);
126
127
_dev->get_semaphore()->give();
128
129
//register compass instance
130
_dev->set_device_type(DEVTYPE_QMC5883P);
131
if (!register_compass(_dev->get_bus_id(), _instance)) {
132
return false;
133
}
134
set_dev_id(_instance, _dev->get_bus_id());
135
136
printf("%s found on bus %u id %u address 0x%02x\n", name,
137
_dev->bus_num(), unsigned(_dev->get_bus_id()), _dev->get_bus_address());
138
139
set_rotation(_instance, _rotation);
140
141
if (_force_external) {
142
set_external(_instance, true);
143
}
144
145
//Enable 100HZ
146
_dev->register_periodic_callback(10000,
147
FUNCTOR_BIND_MEMBER(&AP_Compass_QMC5883P::timer, void));
148
149
return true;
150
151
fail:
152
_dev->get_semaphore()->give();
153
return false;
154
}
155
bool AP_Compass_QMC5883P::_check_whoami()
156
{
157
uint8_t whoami;
158
if (!_dev->read_registers(QMC5883P_REG_ID, &whoami,1)||
159
whoami != QMC5883P_ID_VAL) {
160
return false;
161
}
162
return true;
163
}
164
165
void AP_Compass_QMC5883P::timer()
166
{
167
struct PACKED {
168
int16_t rx;
169
int16_t ry;
170
int16_t rz;
171
} buffer;
172
173
const float range_scale = 1000.0f / 3000.0f;
174
175
uint8_t status;
176
if (!_dev->read_registers(QMC5883P_REG_STATUS,&status,1)) {
177
return;
178
}
179
//new data is ready
180
if (!(status & QMC5883P_STATUS_DATA_READY)) {
181
return;
182
}
183
184
if (!_dev->read_registers(QMC5883P_REG_DATA_OUTPUT_X, (uint8_t *) &buffer, sizeof(buffer))) {
185
return ;
186
}
187
188
auto x = buffer.rx;
189
auto y = buffer.ry;
190
auto z = buffer.rz;
191
192
#if DEBUG
193
printf("mag.x:%d\n",x);
194
printf("mag.y:%d\n",y);
195
printf("mag.z:%d\n",z);
196
#endif
197
198
Vector3f field = Vector3f{x * range_scale, y * range_scale, z * range_scale };
199
200
accumulate_sample(field, _instance, 20);
201
}
202
203
void AP_Compass_QMC5883P::read()
204
{
205
drain_accumulated_samples(_instance);
206
}
207
208
void AP_Compass_QMC5883P::_dump_registers()
209
{
210
printf("QMC5883P registers dump\n");
211
for (uint8_t reg = QMC5883P_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 - ( QMC5883P_REG_DATA_OUTPUT_X-1)) % 16 == 0) {
216
printf("\n");
217
}
218
}
219
}
220
221
#endif //AP_COMPASS_QMC5883P_ENABLED
222
223