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_AK09916.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_AK09916.h"
19
20
#if AP_COMPASS_AK09916_ENABLED
21
22
#include <assert.h>
23
#include <AP_HAL/AP_HAL.h>
24
#include <utility>
25
#include <AP_Math/AP_Math.h>
26
#include <stdio.h>
27
#include <AP_InertialSensor/AP_InertialSensor_Invensensev2.h>
28
#include <GCS_MAVLink/GCS.h>
29
#include <AP_BoardConfig/AP_BoardConfig.h>
30
31
extern const AP_HAL::HAL &hal;
32
33
#define REG_COMPANY_ID 0x00
34
#define REG_DEVICE_ID 0x01
35
#define REG_ST1 0x10
36
#define REG_HXL 0x11
37
#define REG_HXH 0x12
38
#define REG_HYL 0x13
39
#define REG_HYH 0x14
40
#define REG_HZL 0x15
41
#define REG_HZH 0x16
42
#define REG_TMPS 0x17
43
#define REG_ST2 0x18
44
#define REG_CNTL1 0x30
45
#define REG_CNTL2 0x31
46
#define REG_CNTL3 0x32
47
48
#define REG_ICM_WHOAMI 0x00
49
#define REG_ICM_PWR_MGMT_1 0x06
50
#define REG_ICM_INT_PIN_CFG 0x0f
51
52
#define ICM_WHOAMI_VAL 0xEA
53
54
#define AK09915_Device_ID 0x10
55
#define AK09916_Device_ID 0x09
56
#define AK09918_Device_ID 0x0c
57
#define AK09916_MILLIGAUSS_SCALE 10.0f
58
59
extern const AP_HAL::HAL &hal;
60
61
AP_Compass_AK09916::AP_Compass_AK09916(AP_AK09916_BusDriver *bus,
62
bool force_external,
63
enum Rotation rotation)
64
: _bus(bus)
65
, _force_external(force_external)
66
, _rotation(rotation)
67
{
68
}
69
70
AP_Compass_AK09916::~AP_Compass_AK09916()
71
{
72
delete _bus;
73
}
74
75
AP_Compass_Backend *AP_Compass_AK09916::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
76
bool force_external,
77
enum Rotation rotation)
78
{
79
if (!dev) {
80
return nullptr;
81
}
82
AP_AK09916_BusDriver *bus = NEW_NOTHROW AP_AK09916_BusDriver_HALDevice(std::move(dev));
83
if (!bus) {
84
return nullptr;
85
}
86
87
AP_Compass_AK09916 *sensor = NEW_NOTHROW AP_Compass_AK09916(bus, force_external, rotation);
88
if (!sensor || !sensor->init()) {
89
delete sensor;
90
return nullptr;
91
}
92
93
return sensor;
94
}
95
96
#if AP_COMPASS_ICM20948_ENABLED
97
AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
98
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev_icm,
99
bool force_external,
100
enum Rotation rotation)
101
{
102
if (!dev || !dev_icm) {
103
return nullptr;
104
}
105
106
dev->get_semaphore()->take_blocking();
107
108
/* Allow ICM20x48 to shortcut auxiliary bus and host bus */
109
uint8_t rval;
110
uint16_t whoami;
111
uint8_t retries = 5;
112
if (!dev_icm->read_registers(REG_ICM_WHOAMI, &rval, 1) ||
113
rval != ICM_WHOAMI_VAL) {
114
// not an ICM_WHOAMI
115
goto fail;
116
}
117
do {
118
// reset then bring sensor out of sleep mode
119
if (!dev_icm->write_register(REG_ICM_PWR_MGMT_1, 0x80)) {
120
goto fail;
121
}
122
hal.scheduler->delay(10);
123
124
if (!dev_icm->write_register(REG_ICM_PWR_MGMT_1, 0x00)) {
125
goto fail;
126
}
127
hal.scheduler->delay(10);
128
129
// see if ICM20948 is sleeping
130
if (!dev_icm->read_registers(REG_ICM_PWR_MGMT_1, &rval, 1)) {
131
goto fail;
132
}
133
if ((rval & 0x40) == 0) {
134
break;
135
}
136
} while (retries--);
137
138
if (rval & 0x40) {
139
// it didn't come out of sleep
140
goto fail;
141
}
142
143
// initially force i2c bypass off
144
dev_icm->write_register(REG_ICM_INT_PIN_CFG, 0x00);
145
hal.scheduler->delay(1);
146
147
// now check if a AK09916 shows up on the bus. If it does then
148
// we have both a real AK09916 and a ICM20948 with an embedded
149
// AK09916. In that case we will fail the driver load and use
150
// the main AK09916 driver
151
if (dev->read_registers(REG_COMPANY_ID, (uint8_t *)&whoami, 2)) {
152
// a device is replying on the AK09916 I2C address, don't
153
// load the ICM20948
154
DEV_PRINTF("ICM20948: AK09916 bus conflict\n");
155
goto fail;
156
}
157
158
// now force bypass on
159
dev_icm->write_register(REG_ICM_INT_PIN_CFG, 0x02);
160
hal.scheduler->delay(1);
161
dev->get_semaphore()->give();
162
return probe(std::move(dev), force_external, rotation);
163
fail:
164
dev->get_semaphore()->give();
165
return nullptr;
166
}
167
168
// un-named, assume SPI for compat
169
AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948(uint8_t inv2_instance,
170
enum Rotation rotation)
171
{
172
return probe_ICM20948_SPI(inv2_instance,rotation);
173
}
174
175
AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948_SPI(uint8_t inv2_instance,
176
enum Rotation rotation)
177
{
178
#if AP_INERTIALSENSOR_ENABLED
179
AP_InertialSensor &ins = AP::ins();
180
181
AP_AK09916_BusDriver *bus =
182
NEW_NOTHROW AP_AK09916_BusDriver_Auxiliary(ins, HAL_INS_INV2_SPI, inv2_instance, HAL_COMPASS_AK09916_I2C_ADDR);
183
if (!bus) {
184
return nullptr;
185
}
186
187
AP_Compass_AK09916 *sensor = NEW_NOTHROW AP_Compass_AK09916(bus, false, rotation);
188
if (!sensor || !sensor->init()) {
189
delete sensor;
190
return nullptr;
191
}
192
193
return sensor;
194
#else
195
return nullptr;
196
#endif
197
}
198
199
AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948_I2C(uint8_t inv2_instance,
200
enum Rotation rotation)
201
{
202
AP_InertialSensor &ins = AP::ins();
203
204
AP_AK09916_BusDriver *bus =
205
NEW_NOTHROW AP_AK09916_BusDriver_Auxiliary(ins, HAL_INS_INV2_I2C, inv2_instance, HAL_COMPASS_AK09916_I2C_ADDR);
206
if (!bus) {
207
return nullptr;
208
}
209
210
AP_Compass_AK09916 *sensor = NEW_NOTHROW AP_Compass_AK09916(bus, false, rotation);
211
if (!sensor || !sensor->init()) {
212
delete sensor;
213
return nullptr;
214
}
215
216
return sensor;
217
}
218
#endif // AP_COMPASS_ICM20948_ENABLED
219
220
bool AP_Compass_AK09916::init()
221
{
222
AP_HAL::Semaphore *bus_sem = _bus->get_semaphore();
223
224
if (!bus_sem) {
225
return false;
226
}
227
_bus->get_semaphore()->take_blocking();
228
229
if (!_bus->configure()) {
230
DEV_PRINTF("AK09916: Could not configure the bus\n");
231
goto fail;
232
}
233
234
if (!_reset()) {
235
goto fail;
236
}
237
238
if (!_check_id()) {
239
goto fail;
240
}
241
242
// one checked register for mode
243
_bus->setup_checked_registers(1);
244
245
if (!_setup_mode()) {
246
DEV_PRINTF("AK09916: Could not setup mode\n");
247
goto fail;
248
}
249
250
if (!_bus->start_measurements()) {
251
DEV_PRINTF("AK09916: Could not start measurements\n");
252
goto fail;
253
}
254
255
_initialized = true;
256
257
/* register the compass instance in the frontend */
258
_bus->set_device_type(_devtype);
259
if (!register_compass(_bus->get_bus_id(), _compass_instance)) {
260
goto fail;
261
}
262
set_dev_id(_compass_instance, _bus->get_bus_id());
263
264
if (_force_external) {
265
set_external(_compass_instance, true);
266
}
267
268
set_rotation(_compass_instance, _rotation);
269
270
bus_sem->give();
271
272
_bus->register_periodic_callback(10000, FUNCTOR_BIND_MEMBER(&AP_Compass_AK09916::_update, void));
273
274
return true;
275
276
fail:
277
bus_sem->give();
278
return false;
279
}
280
281
void AP_Compass_AK09916::read()
282
{
283
if (!_initialized) {
284
return;
285
}
286
287
drain_accumulated_samples(_compass_instance);
288
}
289
290
void AP_Compass_AK09916::_make_adc_sensitivity_adjustment(Vector3f& field) const
291
{
292
static const float ADC_16BIT_RESOLUTION = 0.15f;
293
294
field *= ADC_16BIT_RESOLUTION;
295
}
296
297
void AP_Compass_AK09916::_update()
298
{
299
struct sample_regs regs = {0};
300
Vector3f raw_field;
301
302
if (!_bus->block_read(REG_ST1, (uint8_t *) &regs, sizeof(regs))) {
303
goto check_registers;
304
}
305
306
if (!(regs.st1 & 0x01)) {
307
no_data++;
308
if (no_data == 5) {
309
_reset();
310
_setup_mode();
311
no_data = 0;
312
}
313
goto check_registers;
314
}
315
no_data = 0;
316
317
/* Check for overflow. See AK09916's datasheet*/
318
if ((regs.st2 & 0x08)) {
319
goto check_registers;
320
}
321
322
raw_field = Vector3f(regs.val[0], regs.val[1], regs.val[2]);
323
324
if (is_zero(raw_field.x) && is_zero(raw_field.y) && is_zero(raw_field.z)) {
325
goto check_registers;
326
}
327
328
_make_adc_sensitivity_adjustment(raw_field);
329
raw_field *= AK09916_MILLIGAUSS_SCALE;
330
331
accumulate_sample(raw_field, _compass_instance, 10);
332
333
check_registers:
334
_bus->check_next_register();
335
}
336
337
bool AP_Compass_AK09916::_check_id()
338
{
339
for (int i = 0; i < 5; i++) {
340
uint8_t deviceid = 0;
341
342
/* Read AK09916's id */
343
if (_bus->register_read(REG_DEVICE_ID, &deviceid)) {
344
switch (deviceid) {
345
case AK09915_Device_ID:
346
_devtype = DEVTYPE_AK09915;
347
return true;
348
case AK09916_Device_ID:
349
_devtype = DEVTYPE_AK09916;
350
return true;
351
case AK09918_Device_ID:
352
_devtype = DEVTYPE_AK09918;
353
return true;
354
}
355
}
356
}
357
358
return false;
359
}
360
361
bool AP_Compass_AK09916::_setup_mode() {
362
return _bus->register_write(REG_CNTL2, 0x08, true); //Continuous Mode 2
363
}
364
365
bool AP_Compass_AK09916::_reset()
366
{
367
return _bus->register_write(REG_CNTL3, 0x01); //Soft Reset
368
}
369
370
/* AP_HAL::I2CDevice implementation of the AK09916 */
371
AP_AK09916_BusDriver_HALDevice::AP_AK09916_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
372
: _dev(std::move(dev))
373
{
374
}
375
376
bool AP_AK09916_BusDriver_HALDevice::block_read(uint8_t reg, uint8_t *buf, uint32_t size)
377
{
378
return _dev->read_registers(reg, buf, size);
379
}
380
381
bool AP_AK09916_BusDriver_HALDevice::register_read(uint8_t reg, uint8_t *val)
382
{
383
return _dev->read_registers(reg, val, 1);
384
}
385
386
bool AP_AK09916_BusDriver_HALDevice::register_write(uint8_t reg, uint8_t val, bool checked)
387
{
388
return _dev->write_register(reg, val, checked);
389
}
390
391
AP_HAL::Semaphore *AP_AK09916_BusDriver_HALDevice::get_semaphore()
392
{
393
return _dev->get_semaphore();
394
}
395
396
AP_HAL::Device::PeriodicHandle AP_AK09916_BusDriver_HALDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
397
{
398
return _dev->register_periodic_callback(period_usec, cb);
399
}
400
401
/* AK09916 on an auxiliary bus of IMU driver */
402
AP_AK09916_BusDriver_Auxiliary::AP_AK09916_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,
403
uint8_t backend_instance, uint8_t addr)
404
{
405
/*
406
* Only initialize members. Fails are handled by configure or while
407
* getting the semaphore
408
*/
409
#if AP_INERTIALSENSOR_ENABLED
410
_bus = ins.get_auxiliary_bus(backend_id, backend_instance);
411
if (!_bus) {
412
return;
413
}
414
415
_slave = _bus->request_next_slave(addr);
416
#endif
417
}
418
419
AP_AK09916_BusDriver_Auxiliary::~AP_AK09916_BusDriver_Auxiliary()
420
{
421
/* After started it's owned by AuxiliaryBus */
422
if (!_started) {
423
delete _slave;
424
}
425
}
426
427
bool AP_AK09916_BusDriver_Auxiliary::block_read(uint8_t reg, uint8_t *buf, uint32_t size)
428
{
429
if (_started) {
430
/*
431
* We can only read a block when reading the block of sample values -
432
* calling with any other value is a mistake
433
*/
434
if (reg != REG_ST1) {
435
return false;
436
}
437
438
int n = _slave->read(buf);
439
return n == static_cast<int>(size);
440
}
441
442
int r = _slave->passthrough_read(reg, buf, size);
443
444
return r > 0 && static_cast<uint32_t>(r) == size;
445
}
446
447
bool AP_AK09916_BusDriver_Auxiliary::register_read(uint8_t reg, uint8_t *val)
448
{
449
return _slave->passthrough_read(reg, val, 1) == 1;
450
}
451
452
bool AP_AK09916_BusDriver_Auxiliary::register_write(uint8_t reg, uint8_t val, bool checked)
453
{
454
(void)checked;
455
return _slave->passthrough_write(reg, val) == 1;
456
}
457
458
AP_HAL::Semaphore *AP_AK09916_BusDriver_Auxiliary::get_semaphore()
459
{
460
return _bus ? _bus->get_semaphore() : nullptr;
461
}
462
463
bool AP_AK09916_BusDriver_Auxiliary::configure()
464
{
465
if (!_bus || !_slave) {
466
return false;
467
}
468
return true;
469
}
470
471
bool AP_AK09916_BusDriver_Auxiliary::start_measurements()
472
{
473
if (_bus->register_periodic_read(_slave, REG_ST1, sizeof(AP_Compass_AK09916::sample_regs)) < 0) {
474
return false;
475
}
476
477
_started = true;
478
479
return true;
480
}
481
482
AP_HAL::Device::PeriodicHandle AP_AK09916_BusDriver_Auxiliary::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
483
{
484
return _bus->register_periodic_callback(period_usec, cb);
485
}
486
487
// set device type within a device class
488
void AP_AK09916_BusDriver_Auxiliary::set_device_type(uint8_t devtype)
489
{
490
_bus->set_device_type(devtype);
491
}
492
493
// return 24 bit bus identifier
494
uint32_t AP_AK09916_BusDriver_Auxiliary::get_bus_id(void) const
495
{
496
return _bus->get_bus_id();
497
}
498
499
#endif // AP_COMPASS_AK09916_ENABLED
500
501