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_MMC3416.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
/*
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::I2CDevice> 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(), compass_instance)) {
97
return false;
98
}
99
100
set_dev_id(compass_instance, dev->get_bus_id());
101
102
printf("Found a MMC3416 on 0x%x as compass %u\n", unsigned(dev->get_bus_id()), compass_instance);
103
104
set_rotation(compass_instance, rotation);
105
106
if (force_external) {
107
set_external(compass_instance, true);
108
}
109
110
dev->set_retries(1);
111
112
// call timer() at 100Hz
113
dev->register_periodic_callback(10000,
114
FUNCTOR_BIND_MEMBER(&AP_Compass_MMC3416::timer, void));
115
116
// wait 250ms for the compass to make it's initial readings
117
hal.scheduler->delay(250);
118
119
return true;
120
}
121
122
void AP_Compass_MMC3416::timer()
123
{
124
const uint16_t measure_count_limit = 50;
125
const uint16_t zero_offset = 32768; // 16 bit mode
126
const uint16_t sensitivity = 2048; // counts per Gauss, 16 bit mode
127
const float counts_to_milliGauss = 1.0e3f / sensitivity;
128
129
uint32_t now = AP_HAL::millis();
130
if (now - last_sample_ms > 500) {
131
// seems to be stuck or on first sample, reset state machine
132
state = STATE_REFILL1;
133
last_sample_ms = now;
134
}
135
136
/*
137
we use the SET/RESET method to remove bridge offset every
138
measure_count_limit measurements. This involves a fairly complex
139
state machine, but means we are much less sensitive to
140
temperature changes
141
*/
142
switch (state) {
143
case STATE_REFILL1:
144
if (dev->write_register(REG_CONTROL0, REG_CONTROL0_REFILL)) {
145
state = STATE_REFILL1_WAIT;
146
refill_start_ms = AP_HAL::millis();
147
}
148
break;
149
150
case STATE_REFILL1_WAIT: {
151
uint8_t status;
152
if (AP_HAL::millis() - refill_start_ms > MIN_DELAY_SET_RESET &&
153
dev->read_registers(REG_STATUS, &status, 1) &&
154
(status & 0x02) == 0) {
155
if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_SET) ||
156
!dev->write_register(REG_CONTROL0, REG_CONTROL0_TM)) { // Take Measurement
157
state = STATE_REFILL1;
158
} else {
159
state = STATE_MEASURE_WAIT1;
160
}
161
}
162
break;
163
}
164
165
case STATE_MEASURE_WAIT1: {
166
uint8_t status;
167
if (dev->read_registers(REG_STATUS, &status, 1) && (status & 1)) {
168
if (!dev->read_registers(REG_XOUT_L, (uint8_t *)&data0[0], 6)) {
169
state = STATE_REFILL1;
170
break;
171
}
172
if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_REFILL)) {
173
state = STATE_REFILL1;
174
} else {
175
state = STATE_REFILL2_WAIT;
176
refill_start_ms = AP_HAL::millis();
177
}
178
}
179
break;
180
}
181
182
case STATE_REFILL2_WAIT: {
183
uint8_t status;
184
if (AP_HAL::millis() - refill_start_ms > MIN_DELAY_SET_RESET &&
185
dev->read_registers(REG_STATUS, &status, 1) &&
186
(status & 0x02) == 0) {
187
if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_RESET) ||
188
!dev->write_register(REG_CONTROL0, REG_CONTROL0_TM)) { // Take Measurement
189
state = STATE_REFILL1;
190
} else {
191
state = STATE_MEASURE_WAIT2;
192
}
193
}
194
break;
195
}
196
197
case STATE_MEASURE_WAIT2: {
198
uint8_t status;
199
if (!dev->read_registers(REG_STATUS, &status, 1) || !(status & 1)) {
200
break;
201
}
202
uint16_t data1[3];
203
if (!dev->read_registers(REG_XOUT_L, (uint8_t *)&data1[0], 6)) {
204
state = STATE_REFILL1;
205
break;
206
}
207
Vector3f field;
208
209
/*
210
calculate field and offset
211
*/
212
Vector3f f1(float(data0[0]) - zero_offset,
213
float(data0[1]) - zero_offset,
214
float(data0[2]) - zero_offset);
215
Vector3f f2(float(data1[0]) - zero_offset,
216
float(data1[1]) - zero_offset,
217
float(data1[2]) - zero_offset);
218
field = (f1 - f2) * (counts_to_milliGauss / 2);
219
Vector3f new_offset = (f1 + f2) * (counts_to_milliGauss / 2);
220
if (!have_initial_offset) {
221
offset = new_offset;
222
have_initial_offset = true;
223
} else {
224
// low pass changes to the offset
225
offset = offset * 0.95f + new_offset * 0.05f;
226
}
227
228
#if 0
229
// @LoggerMessage: MMO
230
// @Description: MMC3416 compass data
231
// @Field: TimeUS: Time since system startup
232
// @Field: Nx: new measurement X axis
233
// @Field: Ny: new measurement Y axis
234
// @Field: Nz: new measurement Z axis
235
// @Field: Ox: new offset X axis
236
// @Field: Oy: new offset Y axis
237
// @Field: Oz: new offset Z axis
238
AP::logger().Write("MMO", "TimeUS,Nx,Ny,Nz,Ox,Oy,Oz", "Qffffff",
239
AP_HAL::micros64(),
240
(double)new_offset.x,
241
(double)new_offset.y,
242
(double)new_offset.z,
243
(double)offset.x,
244
(double)offset.y,
245
(double)offset.z);
246
printf("F(%.1f %.1f %.1f) O(%.1f %.1f %.1f)\n",
247
field.x, field.y, field.z,
248
offset.x, offset.y, offset.z);
249
#endif
250
251
last_sample_ms = AP_HAL::millis();
252
253
// sensor is not FRD
254
field.y = -field.y;
255
256
accumulate_sample(field, compass_instance);
257
258
if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_TM)) {
259
state = STATE_REFILL1;
260
} else {
261
state = STATE_MEASURE_WAIT3;
262
}
263
break;
264
}
265
266
case STATE_MEASURE_WAIT3: {
267
uint8_t status;
268
if (!dev->read_registers(REG_STATUS, &status, 1) || !(status & 1)) {
269
break;
270
}
271
uint16_t data1[3];
272
if (!dev->read_registers(REG_XOUT_L, (uint8_t *)&data1[0], 6)) {
273
state = STATE_REFILL1;
274
break;
275
}
276
Vector3f field(float(data1[0]) - zero_offset,
277
float(data1[1]) - zero_offset,
278
float(data1[2]) - zero_offset);
279
field *= -counts_to_milliGauss;
280
field += offset;
281
282
// sensor is not FRD
283
field.y = -field.y;
284
285
last_sample_ms = AP_HAL::millis();
286
accumulate_sample(field, compass_instance);
287
288
// we stay in STATE_MEASURE_WAIT3 for measure_count_limit cycles
289
if (measure_count++ >= measure_count_limit) {
290
measure_count = 0;
291
state = STATE_REFILL1;
292
} else {
293
if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_TM)) { // Take Measurement
294
state = STATE_REFILL1;
295
}
296
}
297
break;
298
}
299
}
300
}
301
302
void AP_Compass_MMC3416::read()
303
{
304
drain_accumulated_samples(compass_instance);
305
}
306
307
#endif // AP_COMPASS_MMC3416_ENABLED
308
309