Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Compass/AP_Compass_AK8963.cpp
9460 views
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
#include "AP_Compass_AK8963.h"
17
18
#if AP_COMPASS_AK8963_ENABLED
19
20
#include <assert.h>
21
#include <utility>
22
23
#include <AP_Math/AP_Math.h>
24
#include <AP_HAL/AP_HAL.h>
25
26
#include <AP_InertialSensor/AP_InertialSensor_Invensense.h>
27
28
#define AK8963_I2C_ADDR 0x0c
29
30
#define AK8963_WIA 0x00
31
# define AK8963_Device_ID 0x48
32
33
#define AK8963_HXL 0x03
34
35
/* bit definitions for AK8963 CNTL1 */
36
#define AK8963_CNTL1 0x0A
37
# define AK8963_CONTINUOUS_MODE1 0x02
38
# define AK8963_CONTINUOUS_MODE2 0x06
39
# define AK8963_SELFTEST_MODE 0x08
40
# define AK8963_POWERDOWN_MODE 0x00
41
# define AK8963_FUSE_MODE 0x0f
42
# define AK8963_16BIT_ADC 0x10
43
# define AK8963_14BIT_ADC 0x00
44
45
#define AK8963_CNTL2 0x0B
46
# define AK8963_RESET 0x01
47
48
#define AK8963_ASAX 0x10
49
50
#define AK8963_MILLIGAUSS_SCALE 10.0f
51
52
extern const AP_HAL::HAL &hal;
53
54
AP_Compass_AK8963::AP_Compass_AK8963(AP_AK8963_BusDriver *bus,
55
enum Rotation rotation)
56
: _bus(bus)
57
, _rotation(rotation)
58
{
59
}
60
61
AP_Compass_AK8963::~AP_Compass_AK8963()
62
{
63
delete _bus;
64
}
65
66
AP_Compass_Backend *AP_Compass_AK8963::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
67
enum Rotation rotation)
68
{
69
if (!dev) {
70
return nullptr;
71
}
72
AP_AK8963_BusDriver *bus = NEW_NOTHROW AP_AK8963_BusDriver_HALDevice(std::move(dev));
73
if (!bus) {
74
return nullptr;
75
}
76
77
AP_Compass_AK8963 *sensor = NEW_NOTHROW AP_Compass_AK8963(bus, rotation);
78
if (!sensor || !sensor->init()) {
79
delete sensor;
80
return nullptr;
81
}
82
83
return sensor;
84
}
85
86
AP_Compass_Backend *AP_Compass_AK8963::probe_mpu9250(AP_HAL::OwnPtr<AP_HAL::Device> dev,
87
enum Rotation rotation)
88
{
89
if (!dev) {
90
return nullptr;
91
}
92
#if AP_INERTIALSENSOR_ENABLED
93
AP_InertialSensor &ins = *AP_InertialSensor::get_singleton();
94
95
/* Allow MPU9250 to shortcut auxiliary bus and host bus */
96
ins.detect_backends();
97
#endif
98
99
return probe(std::move(dev), rotation);
100
}
101
102
AP_Compass_Backend *AP_Compass_AK8963::probe_mpu9250(uint8_t mpu9250_instance,
103
enum Rotation rotation)
104
{
105
#if AP_INERTIALSENSOR_ENABLED
106
AP_InertialSensor &ins = *AP_InertialSensor::get_singleton();
107
108
AP_AK8963_BusDriver *bus =
109
NEW_NOTHROW AP_AK8963_BusDriver_Auxiliary(ins, HAL_INS_MPU9250_SPI, mpu9250_instance, AK8963_I2C_ADDR);
110
if (!bus) {
111
return nullptr;
112
}
113
114
AP_Compass_AK8963 *sensor = NEW_NOTHROW AP_Compass_AK8963(bus, rotation);
115
if (!sensor || !sensor->init()) {
116
delete sensor;
117
return nullptr;
118
}
119
120
return sensor;
121
#else
122
return nullptr;
123
#endif
124
125
}
126
127
bool AP_Compass_AK8963::init()
128
{
129
AP_HAL::Semaphore *bus_sem = _bus->get_semaphore();
130
131
if (!bus_sem) {
132
return false;
133
}
134
_bus->get_semaphore()->take_blocking();
135
136
if (!_bus->configure()) {
137
DEV_PRINTF("AK8963: Could not configure the bus\n");
138
goto fail;
139
}
140
141
if (!_check_id()) {
142
DEV_PRINTF("AK8963: Wrong id\n");
143
goto fail;
144
}
145
146
if (!_calibrate()) {
147
DEV_PRINTF("AK8963: Could not read calibration data\n");
148
goto fail;
149
}
150
151
if (!_setup_mode()) {
152
DEV_PRINTF("AK8963: Could not setup mode\n");
153
goto fail;
154
}
155
156
if (!_bus->start_measurements()) {
157
DEV_PRINTF("AK8963: Could not start measurements\n");
158
goto fail;
159
}
160
161
_initialized = true;
162
163
/* register the compass instance in the frontend */
164
_bus->set_device_type(DEVTYPE_AK8963);
165
if (!register_compass(_bus->get_bus_id())) {
166
goto fail;
167
}
168
169
set_rotation(_rotation);
170
bus_sem->give();
171
172
_bus->register_periodic_callback(10000, FUNCTOR_BIND_MEMBER(&AP_Compass_AK8963::_update, void));
173
174
return true;
175
176
fail:
177
bus_sem->give();
178
return false;
179
}
180
181
void AP_Compass_AK8963::read()
182
{
183
if (!_initialized) {
184
return;
185
}
186
187
drain_accumulated_samples();
188
}
189
190
void AP_Compass_AK8963::_make_adc_sensitivity_adjustment(Vector3f& field) const
191
{
192
static const float ADC_16BIT_RESOLUTION = 0.15f;
193
194
field *= ADC_16BIT_RESOLUTION;
195
}
196
197
void AP_Compass_AK8963::_make_factory_sensitivity_adjustment(Vector3f& field) const
198
{
199
field.x *= _magnetometer_ASA[0];
200
field.y *= _magnetometer_ASA[1];
201
field.z *= _magnetometer_ASA[2];
202
}
203
204
void AP_Compass_AK8963::_update()
205
{
206
struct sample_regs regs;
207
Vector3f raw_field;
208
209
if (!_bus->block_read(AK8963_HXL, (uint8_t *) &regs, sizeof(regs))) {
210
return;
211
}
212
213
/* Check for overflow. See AK8963's datasheet, section
214
* 6.4.3.6 - Magnetic Sensor Overflow. */
215
if ((regs.st2 & 0x08)) {
216
return;
217
}
218
219
raw_field = Vector3f(regs.val[0], regs.val[1], regs.val[2]);
220
221
if (is_zero(raw_field.x) && is_zero(raw_field.y) && is_zero(raw_field.z)) {
222
return;
223
}
224
225
_make_factory_sensitivity_adjustment(raw_field);
226
_make_adc_sensitivity_adjustment(raw_field);
227
raw_field *= AK8963_MILLIGAUSS_SCALE;
228
229
accumulate_sample(raw_field, 10);
230
}
231
232
bool AP_Compass_AK8963::_check_id()
233
{
234
for (int i = 0; i < 5; i++) {
235
uint8_t deviceid = 0;
236
237
/* Read AK8963's id */
238
if (_bus->register_read(AK8963_WIA, &deviceid) &&
239
deviceid == AK8963_Device_ID) {
240
return true;
241
}
242
}
243
244
return false;
245
}
246
247
bool AP_Compass_AK8963::_setup_mode() {
248
return _bus->register_write(AK8963_CNTL1, AK8963_CONTINUOUS_MODE2 | AK8963_16BIT_ADC);
249
}
250
251
bool AP_Compass_AK8963::_reset()
252
{
253
return _bus->register_write(AK8963_CNTL2, AK8963_RESET);
254
}
255
256
257
bool AP_Compass_AK8963::_calibrate()
258
{
259
/* Enable FUSE-mode in order to be able to read calibration data */
260
_bus->register_write(AK8963_CNTL1, AK8963_FUSE_MODE | AK8963_16BIT_ADC);
261
262
uint8_t response[3];
263
264
_bus->block_read(AK8963_ASAX, response, 3);
265
266
for (int i = 0; i < 3; i++) {
267
float data = response[i];
268
_magnetometer_ASA[i] = ((data - 128) / 256 + 1);
269
}
270
271
return true;
272
}
273
274
/* AP_HAL::Device implementation of the AK8963 */
275
AP_AK8963_BusDriver_HALDevice::AP_AK8963_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev)
276
: _dev(std::move(dev))
277
{
278
}
279
280
bool AP_AK8963_BusDriver_HALDevice::block_read(uint8_t reg, uint8_t *buf, uint32_t size)
281
{
282
return _dev->read_registers(reg, buf, size);
283
}
284
285
bool AP_AK8963_BusDriver_HALDevice::register_read(uint8_t reg, uint8_t *val)
286
{
287
return _dev->read_registers(reg, val, 1);
288
}
289
290
bool AP_AK8963_BusDriver_HALDevice::register_write(uint8_t reg, uint8_t val)
291
{
292
return _dev->write_register(reg, val);
293
}
294
295
AP_HAL::Semaphore *AP_AK8963_BusDriver_HALDevice::get_semaphore()
296
{
297
return _dev->get_semaphore();
298
}
299
300
AP_HAL::Device::PeriodicHandle AP_AK8963_BusDriver_HALDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
301
{
302
return _dev->register_periodic_callback(period_usec, cb);
303
}
304
305
/* AK8963 on an auxiliary bus of IMU driver */
306
AP_AK8963_BusDriver_Auxiliary::AP_AK8963_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,
307
uint8_t backend_instance, uint8_t addr)
308
{
309
/*
310
* Only initialize members. Fails are handled by configure or while
311
* getting the semaphore
312
*/
313
#if AP_INERTIALSENSOR_ENABLED
314
_bus = ins.get_auxiliary_bus(backend_id, backend_instance);
315
if (!_bus) {
316
return;
317
}
318
319
_slave = _bus->request_next_slave(addr);
320
#endif
321
}
322
323
AP_AK8963_BusDriver_Auxiliary::~AP_AK8963_BusDriver_Auxiliary()
324
{
325
/* After started it's owned by AuxiliaryBus */
326
if (!_started) {
327
delete _slave;
328
}
329
}
330
331
bool AP_AK8963_BusDriver_Auxiliary::block_read(uint8_t reg, uint8_t *buf, uint32_t size)
332
{
333
if (_started) {
334
/*
335
* We can only read a block when reading the block of sample values -
336
* calling with any other value is a mistake
337
*/
338
if (reg != AK8963_HXL) {
339
return false;
340
}
341
342
int n = _slave->read(buf);
343
return n == static_cast<int>(size);
344
}
345
346
int r = _slave->passthrough_read(reg, buf, size);
347
348
return r > 0 && static_cast<uint32_t>(r) == size;
349
}
350
351
bool AP_AK8963_BusDriver_Auxiliary::register_read(uint8_t reg, uint8_t *val)
352
{
353
return _slave->passthrough_read(reg, val, 1) == 1;
354
}
355
356
bool AP_AK8963_BusDriver_Auxiliary::register_write(uint8_t reg, uint8_t val)
357
{
358
return _slave->passthrough_write(reg, val) == 1;
359
}
360
361
AP_HAL::Semaphore *AP_AK8963_BusDriver_Auxiliary::get_semaphore()
362
{
363
return _bus ? _bus->get_semaphore() : nullptr;
364
}
365
366
bool AP_AK8963_BusDriver_Auxiliary::configure()
367
{
368
if (!_bus || !_slave) {
369
return false;
370
}
371
return true;
372
}
373
374
bool AP_AK8963_BusDriver_Auxiliary::start_measurements()
375
{
376
if (_bus->register_periodic_read(_slave, AK8963_HXL, sizeof(AP_Compass_AK8963::sample_regs)) < 0) {
377
return false;
378
}
379
380
_started = true;
381
382
return true;
383
}
384
385
AP_HAL::Device::PeriodicHandle AP_AK8963_BusDriver_Auxiliary::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
386
{
387
return _bus->register_periodic_callback(period_usec, cb);
388
}
389
390
// set device type within a device class
391
void AP_AK8963_BusDriver_Auxiliary::set_device_type(uint8_t devtype)
392
{
393
_bus->set_device_type(devtype);
394
}
395
396
// return 24 bit bus identifier
397
uint32_t AP_AK8963_BusDriver_Auxiliary::get_bus_id(void) const
398
{
399
return _bus->get_bus_id();
400
}
401
402
#endif // AP_COMPASS_AK8963_ENABLED
403
404