APM:Libraries
AP_Compass_AK8963.cpp
Go to the documentation of this file.
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 #include <assert.h>
16 #include <utility>
17 
18 #include <AP_Math/AP_Math.h>
19 #include <AP_HAL/AP_HAL.h>
20 
21 #include "AP_Compass_AK8963.h"
23 
24 #define AK8963_I2C_ADDR 0x0c
25 
26 #define AK8963_WIA 0x00
27 # define AK8963_Device_ID 0x48
28 
29 #define AK8963_HXL 0x03
30 
31 /* bit definitions for AK8963 CNTL1 */
32 #define AK8963_CNTL1 0x0A
33 # define AK8963_CONTINUOUS_MODE1 0x02
34 # define AK8963_CONTINUOUS_MODE2 0x06
35 # define AK8963_SELFTEST_MODE 0x08
36 # define AK8963_POWERDOWN_MODE 0x00
37 # define AK8963_FUSE_MODE 0x0f
38 # define AK8963_16BIT_ADC 0x10
39 # define AK8963_14BIT_ADC 0x00
40 
41 #define AK8963_CNTL2 0x0B
42 # define AK8963_RESET 0x01
43 
44 #define AK8963_ASAX 0x10
45 
46 #define AK8963_MILLIGAUSS_SCALE 10.0f
47 
49  int16_t val[3];
50  uint8_t st2;
51 };
52 
53 extern const AP_HAL::HAL &hal;
54 
56  enum Rotation rotation)
57  : AP_Compass_Backend(compass)
58  , _bus(bus)
59  , _rotation(rotation)
60 {
61 }
62 
64 {
65  delete _bus;
66 }
67 
70  enum Rotation rotation)
71 {
72  if (!dev) {
73  return nullptr;
74  }
75  AP_AK8963_BusDriver *bus = new AP_AK8963_BusDriver_HALDevice(std::move(dev));
76  if (!bus) {
77  return nullptr;
78  }
79 
80  AP_Compass_AK8963 *sensor = new AP_Compass_AK8963(compass, bus, rotation);
81  if (!sensor || !sensor->init()) {
82  delete sensor;
83  return nullptr;
84  }
85 
86  return sensor;
87 }
88 
91  enum Rotation rotation)
92 {
93  if (!dev) {
94  return nullptr;
95  }
97 
98  /* Allow MPU9250 to shortcut auxiliary bus and host bus */
99  ins.detect_backends();
100 
101  return probe(compass, std::move(dev), rotation);
102 }
103 
105  enum Rotation rotation)
106 {
108 
109  AP_AK8963_BusDriver *bus =
111  if (!bus) {
112  return nullptr;
113  }
114 
115  AP_Compass_AK8963 *sensor = new AP_Compass_AK8963(compass, bus, rotation);
116  if (!sensor || !sensor->init()) {
117  delete sensor;
118  return nullptr;
119  }
120 
121  return sensor;
122 }
123 
125 {
126  AP_HAL::Semaphore *bus_sem = _bus->get_semaphore();
127 
128  if (!bus_sem || !_bus->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
129  hal.console->printf("AK8963: Unable to get bus semaphore\n");
130  return false;
131  }
132 
133  if (!_bus->configure()) {
134  hal.console->printf("AK8963: Could not configure the bus\n");
135  goto fail;
136  }
137 
138  if (!_check_id()) {
139  hal.console->printf("AK8963: Wrong id\n");
140  goto fail;
141  }
142 
143  if (!_calibrate()) {
144  hal.console->printf("AK8963: Could not read calibration data\n");
145  goto fail;
146  }
147 
148  if (!_setup_mode()) {
149  hal.console->printf("AK8963: Could not setup mode\n");
150  goto fail;
151  }
152 
153  if (!_bus->start_measurements()) {
154  hal.console->printf("AK8963: Could not start measurements\n");
155  goto fail;
156  }
157 
158  _initialized = true;
159 
160  /* register the compass instance in the frontend */
162 
164 
167 
168  bus_sem->give();
169 
171 
172  return true;
173 
174 fail:
175  bus_sem->give();
176  return false;
177 }
178 
180 {
181  if (!_initialized) {
182  return;
183  }
184 
185  if (_sem->take_nonblocking()) {
186  if (_accum_count == 0) {
187  /* We're not ready to publish */
188  _sem->give();
189  return;
190  }
191 
194  _accum_count = 0;
195  _sem->give();
197  }
198 }
199 
201 {
202  static const float ADC_16BIT_RESOLUTION = 0.15f;
203 
204  field *= ADC_16BIT_RESOLUTION;
205 }
206 
208 {
209  field.x *= _magnetometer_ASA[0];
210  field.y *= _magnetometer_ASA[1];
211  field.z *= _magnetometer_ASA[2];
212 }
213 
215 {
216  struct sample_regs regs;
217  Vector3f raw_field;
218 
219  if (!_bus->block_read(AK8963_HXL, (uint8_t *) &regs, sizeof(regs))) {
220  return;
221  }
222 
223  /* Check for overflow. See AK8963's datasheet, section
224  * 6.4.3.6 - Magnetic Sensor Overflow. */
225  if ((regs.st2 & 0x08)) {
226  return;
227  }
228 
229  raw_field = Vector3f(regs.val[0], regs.val[1], regs.val[2]);
230 
231  if (is_zero(raw_field.x) && is_zero(raw_field.y) && is_zero(raw_field.z)) {
232  return;
233  }
234 
237  raw_field *= AK8963_MILLIGAUSS_SCALE;
238 
239  // rotate raw_field from sensor frame to body frame
240  rotate_field(raw_field, _compass_instance);
241 
242  // publish raw_field (uncorrected point sample) for calibration use
244 
245  // correct raw_field for known errors
246  correct_field(raw_field, _compass_instance);
247 
249  _mag_x_accum += raw_field.x;
250  _mag_y_accum += raw_field.y;
251  _mag_z_accum += raw_field.z;
252  _accum_count++;
253  if (_accum_count == 10) {
254  _mag_x_accum /= 2;
255  _mag_y_accum /= 2;
256  _mag_z_accum /= 2;
257  _accum_count = 5;
258  }
259  _sem->give();
260  }
261 }
262 
264 {
265  for (int i = 0; i < 5; i++) {
266  uint8_t deviceid = 0;
267 
268  /* Read AK8963's id */
269  if (_bus->register_read(AK8963_WIA, &deviceid) &&
270  deviceid == AK8963_Device_ID) {
271  return true;
272  }
273  }
274 
275  return false;
276 }
277 
280 }
281 
283 {
285 }
286 
287 
289 {
290  /* Enable FUSE-mode in order to be able to read calibration data */
292 
293  uint8_t response[3];
294 
295  _bus->block_read(AK8963_ASAX, response, 3);
296 
297  for (int i = 0; i < 3; i++) {
298  float data = response[i];
299  _magnetometer_ASA[i] = ((data - 128) / 256 + 1);
300  }
301 
302  return true;
303 }
304 
305 /* AP_HAL::I2CDevice implementation of the AK8963 */
307  : _dev(std::move(dev))
308 {
309 }
310 
311 bool AP_AK8963_BusDriver_HALDevice::block_read(uint8_t reg, uint8_t *buf, uint32_t size)
312 {
313  return _dev->read_registers(reg, buf, size);
314 }
315 
317 {
318  return _dev->read_registers(reg, val, 1);
319 }
320 
322 {
323  return _dev->write_register(reg, val);
324 }
325 
327 {
328  return _dev->get_semaphore();
329 }
330 
332 {
333  return _dev->register_periodic_callback(period_usec, cb);
334 }
335 
336 /* AK8963 on an auxiliary bus of IMU driver */
338  uint8_t backend_instance, uint8_t addr)
339 {
340  /*
341  * Only initialize members. Fails are handled by configure or while
342  * getting the semaphore
343  */
344  _bus = ins.get_auxiliary_bus(backend_id, backend_instance);
345  if (!_bus) {
346  return;
347  }
348 
349  _slave = _bus->request_next_slave(addr);
350 }
351 
353 {
354  /* After started it's owned by AuxiliaryBus */
355  if (!_started) {
356  delete _slave;
357  }
358 }
359 
360 bool AP_AK8963_BusDriver_Auxiliary::block_read(uint8_t reg, uint8_t *buf, uint32_t size)
361 {
362  if (_started) {
363  /*
364  * We can only read a block when reading the block of sample values -
365  * calling with any other value is a mistake
366  */
367  assert(reg == AK8963_HXL);
368 
369  int n = _slave->read(buf);
370  return n == static_cast<int>(size);
371  }
372 
373  int r = _slave->passthrough_read(reg, buf, size);
374 
375  return r > 0 && static_cast<uint32_t>(r) == size;
376 }
377 
379 {
380  return _slave->passthrough_read(reg, val, 1) == 1;
381 }
382 
384 {
385  return _slave->passthrough_write(reg, val) == 1;
386 }
387 
389 {
390  return _bus ? _bus->get_semaphore() : nullptr;
391 }
392 
394 {
395  if (!_bus || !_slave) {
396  return false;
397  }
398  return true;
399 }
400 
402 {
403  if (_bus->register_periodic_read(_slave, AK8963_HXL, sizeof(sample_regs)) < 0) {
404  return false;
405  }
406 
407  _started = true;
408 
409  return true;
410 }
411 
413 {
414  return _bus->register_periodic_callback(period_usec, cb);
415 }
416 
417 // set device type within a device class
419 {
420  _bus->set_device_type(devtype);
421 }
422 
423 // return 24 bit bus identifier
425 {
426  return _bus->get_bus_id();
427 }
#define AK8963_Device_ID
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
Vector3< float > Vector3f
Definition: vector3.h:246
#define HAL_INS_MPU9250_SPI
Definition: AP_HAL_Boards.h:85
virtual bool register_read(uint8_t reg, uint8_t *val)=0
virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size)=0
#define AK8963_I2C_ADDR
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define AK8963_ASAX
void rotate_field(Vector3f &mag, uint8_t instance)
virtual Semaphore * get_semaphore() override=0
void set_device_type(uint8_t devtype) override
virtual void set_device_type(uint8_t devtype)=0
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
virtual AP_HAL::Semaphore * get_semaphore() override
void correct_field(Vector3f &mag, uint8_t i)
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override
virtual bool register_read(uint8_t reg, uint8_t *val) override
bool register_write(uint8_t reg, uint8_t val) override
void set_dev_id(uint8_t instance, uint32_t dev_id)
#define AK8963_MILLIGAUSS_SCALE
virtual bool register_write(uint8_t reg, uint8_t val)=0
Rotation
Definition: rotations.h:27
virtual bool configure()
void fail(const char *why)
Definition: eedump.c:28
static AP_InertialSensor ins
Definition: AHRS_Test.cpp:18
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
virtual AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t, AP_HAL::Device::PeriodicCb)=0
virtual bool take_nonblocking() WARN_IF_UNUSED=0
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
uint8_t register_compass(void) const
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
void _make_factory_sensitivity_adjustment(Vector3f &field) const
AuxiliaryBusSlave * request_next_slave(uint8_t addr)
T y
Definition: vector3.h:67
#define AK8963_CONTINUOUS_MODE2
void * PeriodicHandle
Definition: Device.h:42
AP_AK8963_BusDriver_HALDevice(AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
T z
Definition: vector3.h:67
void read() override
AP_HAL::Semaphore * get_semaphore() override
#define AK8963_16BIT_ADC
static AP_Compass_Backend * probe_mpu9250(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
virtual bool give()=0
bool register_read(uint8_t reg, uint8_t *val) override
static Compass compass
Definition: AHRS_Test.cpp:20
AP_Compass_AK8963(Compass &compass, AP_AK8963_BusDriver *bus, enum Rotation rotation=ROTATION_NONE)
#define AK8963_CNTL2
AP_HAL::Semaphore * _sem
#define AK8963_FUSE_MODE
void _make_adc_sensitivity_adjustment(Vector3f &field) const
AP_AK8963_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id, uint8_t backend_instance, uint8_t addr)
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
enum Rotation _rotation
bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override
void set_rotation(uint8_t instance, enum Rotation rotation)
AuxiliaryBus * get_auxiliary_bus(int16_t backend_id)
uint32_t get_bus_id(void) const override
#define PACKED
Definition: AP_Common.h:28
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
virtual AP_HAL::Semaphore * get_semaphore()=0
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
AP_AK8963_BusDriver * _bus
void publish_raw_field(const Vector3f &mag, uint8_t instance)
virtual bool start_measurements()
virtual bool register_write(uint8_t reg, uint8_t val) override
#define AK8963_HXL
static AP_InertialSensor * get_instance()
#define AK8963_RESET
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
virtual uint32_t get_bus_id(void) const =0
#define AK8963_CNTL1
T x
Definition: vector3.h:67
#define AK8963_WIA