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_AK8963.cpp
Views: 1798
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::I2CDevice> 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::I2CDevice> 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(), _compass_instance)) {
166
goto fail;
167
}
168
set_dev_id(_compass_instance, _bus->get_bus_id());
169
170
set_rotation(_compass_instance, _rotation);
171
bus_sem->give();
172
173
_bus->register_periodic_callback(10000, FUNCTOR_BIND_MEMBER(&AP_Compass_AK8963::_update, void));
174
175
return true;
176
177
fail:
178
bus_sem->give();
179
return false;
180
}
181
182
void AP_Compass_AK8963::read()
183
{
184
if (!_initialized) {
185
return;
186
}
187
188
drain_accumulated_samples(_compass_instance);
189
}
190
191
void AP_Compass_AK8963::_make_adc_sensitivity_adjustment(Vector3f& field) const
192
{
193
static const float ADC_16BIT_RESOLUTION = 0.15f;
194
195
field *= ADC_16BIT_RESOLUTION;
196
}
197
198
void AP_Compass_AK8963::_make_factory_sensitivity_adjustment(Vector3f& field) const
199
{
200
field.x *= _magnetometer_ASA[0];
201
field.y *= _magnetometer_ASA[1];
202
field.z *= _magnetometer_ASA[2];
203
}
204
205
void AP_Compass_AK8963::_update()
206
{
207
struct sample_regs regs;
208
Vector3f raw_field;
209
210
if (!_bus->block_read(AK8963_HXL, (uint8_t *) &regs, sizeof(regs))) {
211
return;
212
}
213
214
/* Check for overflow. See AK8963's datasheet, section
215
* 6.4.3.6 - Magnetic Sensor Overflow. */
216
if ((regs.st2 & 0x08)) {
217
return;
218
}
219
220
raw_field = Vector3f(regs.val[0], regs.val[1], regs.val[2]);
221
222
if (is_zero(raw_field.x) && is_zero(raw_field.y) && is_zero(raw_field.z)) {
223
return;
224
}
225
226
_make_factory_sensitivity_adjustment(raw_field);
227
_make_adc_sensitivity_adjustment(raw_field);
228
raw_field *= AK8963_MILLIGAUSS_SCALE;
229
230
accumulate_sample(raw_field, _compass_instance, 10);
231
}
232
233
bool AP_Compass_AK8963::_check_id()
234
{
235
for (int i = 0; i < 5; i++) {
236
uint8_t deviceid = 0;
237
238
/* Read AK8963's id */
239
if (_bus->register_read(AK8963_WIA, &deviceid) &&
240
deviceid == AK8963_Device_ID) {
241
return true;
242
}
243
}
244
245
return false;
246
}
247
248
bool AP_Compass_AK8963::_setup_mode() {
249
return _bus->register_write(AK8963_CNTL1, AK8963_CONTINUOUS_MODE2 | AK8963_16BIT_ADC);
250
}
251
252
bool AP_Compass_AK8963::_reset()
253
{
254
return _bus->register_write(AK8963_CNTL2, AK8963_RESET);
255
}
256
257
258
bool AP_Compass_AK8963::_calibrate()
259
{
260
/* Enable FUSE-mode in order to be able to read calibration data */
261
_bus->register_write(AK8963_CNTL1, AK8963_FUSE_MODE | AK8963_16BIT_ADC);
262
263
uint8_t response[3];
264
265
_bus->block_read(AK8963_ASAX, response, 3);
266
267
for (int i = 0; i < 3; i++) {
268
float data = response[i];
269
_magnetometer_ASA[i] = ((data - 128) / 256 + 1);
270
}
271
272
return true;
273
}
274
275
/* AP_HAL::I2CDevice implementation of the AK8963 */
276
AP_AK8963_BusDriver_HALDevice::AP_AK8963_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
277
: _dev(std::move(dev))
278
{
279
}
280
281
bool AP_AK8963_BusDriver_HALDevice::block_read(uint8_t reg, uint8_t *buf, uint32_t size)
282
{
283
return _dev->read_registers(reg, buf, size);
284
}
285
286
bool AP_AK8963_BusDriver_HALDevice::register_read(uint8_t reg, uint8_t *val)
287
{
288
return _dev->read_registers(reg, val, 1);
289
}
290
291
bool AP_AK8963_BusDriver_HALDevice::register_write(uint8_t reg, uint8_t val)
292
{
293
return _dev->write_register(reg, val);
294
}
295
296
AP_HAL::Semaphore *AP_AK8963_BusDriver_HALDevice::get_semaphore()
297
{
298
return _dev->get_semaphore();
299
}
300
301
AP_HAL::Device::PeriodicHandle AP_AK8963_BusDriver_HALDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
302
{
303
return _dev->register_periodic_callback(period_usec, cb);
304
}
305
306
/* AK8963 on an auxiliary bus of IMU driver */
307
AP_AK8963_BusDriver_Auxiliary::AP_AK8963_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,
308
uint8_t backend_instance, uint8_t addr)
309
{
310
/*
311
* Only initialize members. Fails are handled by configure or while
312
* getting the semaphore
313
*/
314
#if AP_INERTIALSENSOR_ENABLED
315
_bus = ins.get_auxiliary_bus(backend_id, backend_instance);
316
if (!_bus) {
317
return;
318
}
319
320
_slave = _bus->request_next_slave(addr);
321
#endif
322
}
323
324
AP_AK8963_BusDriver_Auxiliary::~AP_AK8963_BusDriver_Auxiliary()
325
{
326
/* After started it's owned by AuxiliaryBus */
327
if (!_started) {
328
delete _slave;
329
}
330
}
331
332
bool AP_AK8963_BusDriver_Auxiliary::block_read(uint8_t reg, uint8_t *buf, uint32_t size)
333
{
334
if (_started) {
335
/*
336
* We can only read a block when reading the block of sample values -
337
* calling with any other value is a mistake
338
*/
339
if (reg != AK8963_HXL) {
340
return false;
341
}
342
343
int n = _slave->read(buf);
344
return n == static_cast<int>(size);
345
}
346
347
int r = _slave->passthrough_read(reg, buf, size);
348
349
return r > 0 && static_cast<uint32_t>(r) == size;
350
}
351
352
bool AP_AK8963_BusDriver_Auxiliary::register_read(uint8_t reg, uint8_t *val)
353
{
354
return _slave->passthrough_read(reg, val, 1) == 1;
355
}
356
357
bool AP_AK8963_BusDriver_Auxiliary::register_write(uint8_t reg, uint8_t val)
358
{
359
return _slave->passthrough_write(reg, val) == 1;
360
}
361
362
AP_HAL::Semaphore *AP_AK8963_BusDriver_Auxiliary::get_semaphore()
363
{
364
return _bus ? _bus->get_semaphore() : nullptr;
365
}
366
367
bool AP_AK8963_BusDriver_Auxiliary::configure()
368
{
369
if (!_bus || !_slave) {
370
return false;
371
}
372
return true;
373
}
374
375
bool AP_AK8963_BusDriver_Auxiliary::start_measurements()
376
{
377
if (_bus->register_periodic_read(_slave, AK8963_HXL, sizeof(AP_Compass_AK8963::sample_regs)) < 0) {
378
return false;
379
}
380
381
_started = true;
382
383
return true;
384
}
385
386
AP_HAL::Device::PeriodicHandle AP_AK8963_BusDriver_Auxiliary::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
387
{
388
return _bus->register_periodic_callback(period_usec, cb);
389
}
390
391
// set device type within a device class
392
void AP_AK8963_BusDriver_Auxiliary::set_device_type(uint8_t devtype)
393
{
394
_bus->set_device_type(devtype);
395
}
396
397
// return 24 bit bus identifier
398
uint32_t AP_AK8963_BusDriver_Auxiliary::get_bus_id(void) const
399
{
400
return _bus->get_bus_id();
401
}
402
403
#endif // AP_COMPASS_AK8963_ENABLED
404
405