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_MMC5xx3.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
#include "AP_Compass_MMC5xx3.h"
17
18
#if AP_COMPASS_MMC5XX3_ENABLED
19
20
#include <AP_HAL/AP_HAL.h>
21
#include <stdio.h>
22
23
extern const AP_HAL::HAL &hal;
24
25
#define REG_PRODUCT_ID 0x2F
26
#define REG_XOUT_L 0x00
27
#define REG_STATUS 0x08
28
#define REG_CONTROL0 0x09
29
#define REG_CONTROL1 0x0A
30
#define REG_CONTROL2 0x0B
31
32
// bits in REG_CONTROL0
33
#define REG_CONTROL0_RESET 0x10 // Set coil for measuring offset
34
#define REG_CONTROL0_SET 0x08 // Reset coil for measuring offset
35
#define REG_CONTROL0_TMM 0x01 // Take Measurement for Magnetic field
36
#define REG_CONTROL0_TMT 0x02 // Take Measurement for Temperature
37
38
// bits in REG_CONTROL1
39
#define REG_CONTROL1_SW_RST 0x80 // Software reset
40
#define REG_CONTROL1_BW0 0x01
41
#define REG_CONTROL1_BW1 0x02
42
43
#define MMC5983_ID 0x30
44
45
AP_Compass_Backend *AP_Compass_MMC5XX3::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
46
bool force_external,
47
enum Rotation rotation)
48
{
49
if (!dev) {
50
return nullptr;
51
}
52
AP_Compass_MMC5XX3 *sensor = NEW_NOTHROW AP_Compass_MMC5XX3(std::move(dev), force_external, rotation);
53
if (!sensor || !sensor->init()) {
54
delete sensor;
55
return nullptr;
56
}
57
58
return sensor;
59
}
60
61
AP_Compass_MMC5XX3::AP_Compass_MMC5XX3(AP_HAL::OwnPtr<AP_HAL::Device> _dev,
62
bool _force_external,
63
enum Rotation _rotation)
64
: dev(std::move(_dev))
65
, force_external(_force_external)
66
, have_initial_offset(false)
67
, rotation(_rotation)
68
{
69
}
70
71
bool AP_Compass_MMC5XX3::init()
72
{
73
// take i2c bus semaphore
74
WITH_SEMAPHORE(dev->get_semaphore());
75
76
dev->set_retries(10);
77
78
// setup to allow reads on SPI
79
if (dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
80
dev->set_read_flag(0x80);
81
}
82
83
// Reading REG_PRODUCT_ID fails sometimes on SPI, so we retry up to 10 times
84
uint8_t whoami = 0;
85
uint8_t tries = 10;
86
while (whoami == 0 && tries > 0) {
87
tries--;
88
dev->read_registers(REG_PRODUCT_ID, &whoami, 1);
89
hal.scheduler->delay(5);
90
}
91
92
if (whoami != MMC5983_ID) {
93
printf("MMC5983 got unexpected product id: %d, expected: %d\n", whoami, MMC5983_ID);
94
// not a MMC5983
95
return false;
96
}
97
98
// reset sensor
99
dev->write_register(REG_CONTROL1, REG_CONTROL1_SW_RST);
100
101
// 10ms minimum startup time
102
hal.scheduler->delay(15);
103
104
// setup for 100Hz output
105
if (!dev->write_register(REG_CONTROL1, 0)) {
106
return false;
107
}
108
109
110
/* register the compass instance in the frontend */
111
dev->set_device_type(DEVTYPE_MMC5983);
112
if (!register_compass(dev->get_bus_id(), compass_instance)) {
113
return false;
114
}
115
116
set_dev_id(compass_instance, dev->get_bus_id());
117
118
printf("Found a MMC5983 on 0x%x as compass %u\n", unsigned(dev->get_bus_id()), compass_instance);
119
120
set_rotation(compass_instance, rotation);
121
122
if (force_external) {
123
set_external(compass_instance, true);
124
}
125
126
dev->set_retries(1);
127
128
// call timer() at 100Hz
129
dev->register_periodic_callback(10000U,
130
FUNCTOR_BIND_MEMBER(&AP_Compass_MMC5XX3::timer, void));
131
132
return true;
133
}
134
135
void AP_Compass_MMC5XX3::timer()
136
{
137
// recalculate the offset with set/reset operation every measure_count_limit measurements
138
// sensor is read at about 100Hz, so about every 10 seconds
139
const uint16_t measure_count_limit = 1000U;
140
const uint16_t zero_offset = 32768U; // 16 bit mode
141
const uint16_t sensitivity = 4096U; // counts per Gauss, 16 bit mode
142
constexpr float counts_to_milliGauss = 1.0e3f / sensitivity;
143
144
/*
145
we use the SET/RESET method to remove bridge offset every
146
measure_count_limit measurements. This involves a fairly complex
147
state machine, but means we are much less sensitive to
148
temperature changes
149
*/
150
switch (state) {
151
152
// perform a set operation
153
case MMCState::STATE_SET: {
154
if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_SET)) {
155
break;
156
}
157
// minimum time to wait after set/reset before take measurement request is 1ms
158
state = MMCState::STATE_SET_MEASURE;
159
break;
160
}
161
162
// request a measurement for field and offset calculation after set operation
163
case MMCState::STATE_SET_MEASURE: {
164
if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_TMM)) {
165
break;
166
}
167
state = MMCState::STATE_SET_WAIT;
168
break;
169
}
170
171
// wait for measurement to be ready after set operation, then read the
172
// measurement data and request a reset operation
173
case MMCState::STATE_SET_WAIT: {
174
uint8_t status;
175
if (!dev->read_registers(REG_STATUS, &status, 1)) {
176
state = MMCState::STATE_SET;
177
break;
178
}
179
180
// check if measurement is ready
181
if (!(status & 1)) {
182
break;
183
}
184
185
// read measurement
186
if (!dev->read_registers(REG_XOUT_L, (uint8_t *)&data0[0], 6)) {
187
state = MMCState::STATE_SET;
188
break;
189
}
190
191
// request set operation
192
if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_RESET)) {
193
break;
194
}
195
// minimum time to wait after set/reset before take measurement request is 1ms
196
state = MMCState::STATE_RESET_MEASURE;
197
break;
198
}
199
200
// request a measurement for field and offset calculation after reset operation
201
case MMCState::STATE_RESET_MEASURE: {
202
// take measurement request
203
if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_TMM)) {
204
state = MMCState::STATE_SET;
205
break;
206
}
207
208
state = MMCState::STATE_RESET_WAIT;
209
break;
210
}
211
212
// wait for measurement to be ready after reset operation,
213
// then read the measurement data, calculate the field and offset,
214
// and begin requesting field measurements
215
case MMCState::STATE_RESET_WAIT: {
216
uint8_t status;
217
if (!dev->read_registers(REG_STATUS, &status, 1)) {
218
state = MMCState::STATE_SET;
219
break;
220
}
221
// check if measurement is ready
222
if (!(status & 1)) {
223
break;
224
}
225
226
uint8_t data1[6];
227
if (!dev->read_registers(REG_XOUT_L, (uint8_t *)&data1[0], 6)) {
228
state = MMCState::STATE_SET;
229
break;
230
}
231
232
/*
233
calculate field and offset
234
*/
235
Vector3f f1 {float((data0[0] << 8) + data0[1]) - zero_offset,
236
float((data0[2] << 8) + data0[3]) - zero_offset,
237
float((data0[4] << 8) + data0[5]) - zero_offset};
238
Vector3f f2 {float((data1[0] << 8) + data1[1]) - zero_offset,
239
float((data1[2] << 8) + data1[3]) - zero_offset,
240
float((data1[4] << 8) + data1[5]) - zero_offset};
241
242
Vector3f field {(f2 - f1) * counts_to_milliGauss * 0.5f};
243
Vector3f new_offset {(f1 + f2) * counts_to_milliGauss * 0.5f};
244
245
if (!have_initial_offset) {
246
offset = new_offset;
247
have_initial_offset = true;
248
} else {
249
// low pass changes to the offset
250
offset = offset * 0.5f + new_offset * 0.5f;
251
}
252
253
accumulate_sample(field, compass_instance);
254
255
if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_TMM)) {
256
printf("failed to initiate measurement\n");
257
state = MMCState::STATE_SET;
258
} else {
259
state = MMCState::STATE_MEASURE;
260
}
261
262
break;
263
}
264
265
// take repeated field measurements, set/reset is performed again after
266
// measure_count_limit measurements
267
case MMCState::STATE_MEASURE: {
268
uint8_t status;
269
if (!dev->read_registers(REG_STATUS, &status, 1)) {
270
state = MMCState::STATE_SET;
271
break;
272
}
273
274
// check if measurement is ready
275
if (!(status & 1)) {
276
break;
277
}
278
279
uint8_t data1[6];
280
if (!dev->read_registers(REG_XOUT_L, (uint8_t *)&data1[0], 6)) {
281
printf("cant read data\n");
282
state = MMCState::STATE_SET;
283
break;
284
}
285
286
Vector3f field {float((data1[0] << 8) + data1[1]) - zero_offset,
287
float((data1[2] << 8) + data1[3]) - zero_offset,
288
float((data1[4] << 8) + data1[5]) - zero_offset};
289
field *= counts_to_milliGauss;
290
field -= offset;
291
accumulate_sample(field, compass_instance);
292
293
// we stay in STATE_MEASURE for measure_count_limit cycles
294
if (measure_count++ >= measure_count_limit) {
295
measure_count = 0;
296
state = MMCState::STATE_SET;
297
} else {
298
if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_TMM)) { // Take Measurement
299
state = MMCState::STATE_SET;
300
}
301
}
302
break;
303
}
304
}
305
}
306
307
void AP_Compass_MMC5XX3::read()
308
{
309
drain_accumulated_samples(compass_instance);
310
}
311
312
#endif // AP_COMPASS_MMC5XX3_ENABLED
313
314
315