Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Compass/AP_Compass_MMC3416.cpp
9432 views
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
/*
16
Driver by Andrew Tridgell, Nov 2016
17
*/
18
#include "AP_Compass_MMC3416.h"
19
20
#if AP_COMPASS_MMC3416_ENABLED
21
22
#include <AP_HAL/AP_HAL.h>
23
#include <utility>
24
#include <AP_Math/AP_Math.h>
25
#include <stdio.h>
26
#include <AP_Logger/AP_Logger.h>
27
28
extern const AP_HAL::HAL &hal;
29
30
#define REG_PRODUCT_ID 0x20
31
#define REG_XOUT_L 0x00
32
#define REG_STATUS 0x06
33
#define REG_CONTROL0 0x07
34
#define REG_CONTROL1 0x08
35
36
// bits in REG_CONTROL0
37
#define REG_CONTROL0_REFILL 0x80
38
#define REG_CONTROL0_RESET 0x40
39
#define REG_CONTROL0_SET 0x20
40
#define REG_CONTROL0_NB 0x10
41
#define REG_CONTROL0_TM 0x01
42
43
// datasheet says 50ms min for refill
44
#define MIN_DELAY_SET_RESET 50
45
46
AP_Compass_Backend *AP_Compass_MMC3416::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
47
bool force_external,
48
enum Rotation rotation)
49
{
50
if (!dev) {
51
return nullptr;
52
}
53
AP_Compass_MMC3416 *sensor = NEW_NOTHROW AP_Compass_MMC3416(std::move(dev), force_external, rotation);
54
if (!sensor || !sensor->init()) {
55
delete sensor;
56
return nullptr;
57
}
58
59
return sensor;
60
}
61
62
AP_Compass_MMC3416::AP_Compass_MMC3416(AP_HAL::OwnPtr<AP_HAL::Device> _dev,
63
bool _force_external,
64
enum Rotation _rotation)
65
: dev(std::move(_dev))
66
, force_external(_force_external)
67
, rotation(_rotation)
68
{
69
}
70
71
bool AP_Compass_MMC3416::init()
72
{
73
dev->get_semaphore()->take_blocking();
74
75
dev->set_retries(10);
76
77
uint8_t whoami;
78
if (!dev->read_registers(REG_PRODUCT_ID, &whoami, 1) ||
79
whoami != 0x06) {
80
// not a MMC3416
81
dev->get_semaphore()->give();
82
return false;
83
}
84
85
// reset sensor
86
dev->write_register(REG_CONTROL1, 0x80);
87
hal.scheduler->delay(10);
88
89
dev->write_register(REG_CONTROL0, 0x00); // single shot
90
dev->write_register(REG_CONTROL1, 0x00); // 16 bit, 7.92ms
91
92
dev->get_semaphore()->give();
93
94
/* register the compass instance in the frontend */
95
dev->set_device_type(DEVTYPE_MMC3416);
96
if (!register_compass(dev->get_bus_id())) {
97
return false;
98
}
99
100
printf("Found a MMC3416 on 0x%x as compass %u\n", unsigned(dev->get_bus_id()), instance);
101
102
set_rotation(rotation);
103
104
if (force_external) {
105
set_external(true);
106
}
107
108
dev->set_retries(1);
109
110
// call timer() at 100Hz
111
dev->register_periodic_callback(10000,
112
FUNCTOR_BIND_MEMBER(&AP_Compass_MMC3416::timer, void));
113
114
// wait 250ms for the compass to make it's initial readings
115
hal.scheduler->delay(250);
116
117
return true;
118
}
119
120
void AP_Compass_MMC3416::timer()
121
{
122
const uint16_t measure_count_limit = 50;
123
const uint16_t zero_offset = 32768; // 16 bit mode
124
const uint16_t sensitivity = 2048; // counts per Gauss, 16 bit mode
125
const float counts_to_milliGauss = 1.0e3f / sensitivity;
126
127
uint32_t now = AP_HAL::millis();
128
if (now - last_sample_ms > 500) {
129
// seems to be stuck or on first sample, reset state machine
130
state = STATE_REFILL1;
131
last_sample_ms = now;
132
}
133
134
/*
135
we use the SET/RESET method to remove bridge offset every
136
measure_count_limit measurements. This involves a fairly complex
137
state machine, but means we are much less sensitive to
138
temperature changes
139
*/
140
switch (state) {
141
case STATE_REFILL1:
142
if (dev->write_register(REG_CONTROL0, REG_CONTROL0_REFILL)) {
143
state = STATE_REFILL1_WAIT;
144
refill_start_ms = AP_HAL::millis();
145
}
146
break;
147
148
case STATE_REFILL1_WAIT: {
149
uint8_t status;
150
if (AP_HAL::millis() - refill_start_ms > MIN_DELAY_SET_RESET &&
151
dev->read_registers(REG_STATUS, &status, 1) &&
152
(status & 0x02) == 0) {
153
if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_SET) ||
154
!dev->write_register(REG_CONTROL0, REG_CONTROL0_TM)) { // Take Measurement
155
state = STATE_REFILL1;
156
} else {
157
state = STATE_MEASURE_WAIT1;
158
}
159
}
160
break;
161
}
162
163
case STATE_MEASURE_WAIT1: {
164
uint8_t status;
165
if (dev->read_registers(REG_STATUS, &status, 1) && (status & 1)) {
166
if (!dev->read_registers(REG_XOUT_L, (uint8_t *)&data0[0], 6)) {
167
state = STATE_REFILL1;
168
break;
169
}
170
if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_REFILL)) {
171
state = STATE_REFILL1;
172
} else {
173
state = STATE_REFILL2_WAIT;
174
refill_start_ms = AP_HAL::millis();
175
}
176
}
177
break;
178
}
179
180
case STATE_REFILL2_WAIT: {
181
uint8_t status;
182
if (AP_HAL::millis() - refill_start_ms > MIN_DELAY_SET_RESET &&
183
dev->read_registers(REG_STATUS, &status, 1) &&
184
(status & 0x02) == 0) {
185
if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_RESET) ||
186
!dev->write_register(REG_CONTROL0, REG_CONTROL0_TM)) { // Take Measurement
187
state = STATE_REFILL1;
188
} else {
189
state = STATE_MEASURE_WAIT2;
190
}
191
}
192
break;
193
}
194
195
case STATE_MEASURE_WAIT2: {
196
uint8_t status;
197
if (!dev->read_registers(REG_STATUS, &status, 1) || !(status & 1)) {
198
break;
199
}
200
uint16_t data1[3];
201
if (!dev->read_registers(REG_XOUT_L, (uint8_t *)&data1[0], 6)) {
202
state = STATE_REFILL1;
203
break;
204
}
205
Vector3f field;
206
207
/*
208
calculate field and offset
209
*/
210
Vector3f f1(float(data0[0]) - zero_offset,
211
float(data0[1]) - zero_offset,
212
float(data0[2]) - zero_offset);
213
Vector3f f2(float(data1[0]) - zero_offset,
214
float(data1[1]) - zero_offset,
215
float(data1[2]) - zero_offset);
216
field = (f1 - f2) * (counts_to_milliGauss / 2);
217
Vector3f new_offset = (f1 + f2) * (counts_to_milliGauss / 2);
218
if (!have_initial_offset) {
219
offset = new_offset;
220
have_initial_offset = true;
221
} else {
222
// low pass changes to the offset
223
offset = offset * 0.95f + new_offset * 0.05f;
224
}
225
226
#if 0
227
// @LoggerMessage: MMO
228
// @Description: MMC3416 compass data
229
// @Field: TimeUS: Time since system startup
230
// @Field: Nx: new measurement X axis
231
// @Field: Ny: new measurement Y axis
232
// @Field: Nz: new measurement Z axis
233
// @Field: Ox: new offset X axis
234
// @Field: Oy: new offset Y axis
235
// @Field: Oz: new offset Z axis
236
AP::logger().Write("MMO", "TimeUS,Nx,Ny,Nz,Ox,Oy,Oz", "Qffffff",
237
AP_HAL::micros64(),
238
(double)new_offset.x,
239
(double)new_offset.y,
240
(double)new_offset.z,
241
(double)offset.x,
242
(double)offset.y,
243
(double)offset.z);
244
printf("F(%.1f %.1f %.1f) O(%.1f %.1f %.1f)\n",
245
field.x, field.y, field.z,
246
offset.x, offset.y, offset.z);
247
#endif
248
249
last_sample_ms = AP_HAL::millis();
250
251
// sensor is not FRD
252
field.y = -field.y;
253
254
accumulate_sample(field);
255
256
if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_TM)) {
257
state = STATE_REFILL1;
258
} else {
259
state = STATE_MEASURE_WAIT3;
260
}
261
break;
262
}
263
264
case STATE_MEASURE_WAIT3: {
265
uint8_t status;
266
if (!dev->read_registers(REG_STATUS, &status, 1) || !(status & 1)) {
267
break;
268
}
269
uint16_t data1[3];
270
if (!dev->read_registers(REG_XOUT_L, (uint8_t *)&data1[0], 6)) {
271
state = STATE_REFILL1;
272
break;
273
}
274
Vector3f field(float(data1[0]) - zero_offset,
275
float(data1[1]) - zero_offset,
276
float(data1[2]) - zero_offset);
277
field *= -counts_to_milliGauss;
278
field += offset;
279
280
// sensor is not FRD
281
field.y = -field.y;
282
283
last_sample_ms = AP_HAL::millis();
284
accumulate_sample(field);
285
286
// we stay in STATE_MEASURE_WAIT3 for measure_count_limit cycles
287
if (measure_count++ >= measure_count_limit) {
288
measure_count = 0;
289
state = STATE_REFILL1;
290
} else {
291
if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_TM)) { // Take Measurement
292
state = STATE_REFILL1;
293
}
294
}
295
break;
296
}
297
}
298
}
299
300
void AP_Compass_MMC3416::read()
301
{
302
drain_accumulated_samples();
303
}
304
305
#endif // AP_COMPASS_MMC3416_ENABLED
306
307