APM:Libraries
AP_Compass_AK09916.cpp
Go to the documentation of this file.
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 #include <AP_HAL/AP_HAL.h>
21 #include <utility>
22 #include <AP_Math/AP_Math.h>
23 #include <stdio.h>
24 
25 #define REG_COMPANY_ID 0x00
26 #define REG_DEVICE_ID 0x01
27 #define REG_ST1 0x10
28 #define REG_HXL 0x11
29 #define REG_HXH 0x12
30 #define REG_HYL 0x13
31 #define REG_HYH 0x14
32 #define REG_HZL 0x15
33 #define REG_HZH 0x16
34 #define REG_TMPS 0x17
35 #define REG_ST2 0x18
36 #define REG_CNTL1 0x30
37 #define REG_CNTL2 0x31
38 #define REG_CNTL3 0x32
39 
40 #define REG_ICM_WHOAMI 0x00
41 #define REG_ICM_PWR_MGMT_1 0x06
42 #define REG_ICM_INT_PIN_CFG 0x0f
43 
44 #define ICM_WHOAMI_VAL 0xEA
45 
46 extern const AP_HAL::HAL &hal;
47 
48 /*
49  probe for AK09916 directly on I2C
50  */
53  bool force_external,
54  enum Rotation rotation)
55 {
56  if (!dev) {
57  return nullptr;
58  }
59  AP_Compass_AK09916 *sensor = new AP_Compass_AK09916(compass, std::move(dev), nullptr,
60  force_external,
61  rotation, AK09916_I2C);
62  if (!sensor || !sensor->init()) {
63  delete sensor;
64  return nullptr;
65  }
66 
67  return sensor;
68 }
69 
70 
71 /*
72  probe for AK09916 connected via an ICM20948
73  */
77  bool force_external,
78  enum Rotation rotation)
79 {
80  if (!dev) {
81  return nullptr;
82  }
83  AP_Compass_AK09916 *sensor = new AP_Compass_AK09916(compass, std::move(dev), std::move(dev_icm),
84  force_external,
85  rotation, AK09916_ICM20948_I2C);
86  if (!sensor || !sensor->init()) {
87  delete sensor;
88  return nullptr;
89  }
90 
91  return sensor;
92 }
93 
97  bool _force_external,
98  enum Rotation _rotation,
99  enum bus_type _bus_type)
100  : AP_Compass_Backend(compass)
101  , bus_type(_bus_type)
102  , dev(std::move(_dev))
103  , dev_icm(std::move(_dev_icm))
104  , force_external(_force_external)
105  , rotation(_rotation)
106 {
107 }
108 
110 {
112  return false;
113  }
114 
116  uint8_t rval;
117  if (!dev_icm->read_registers(REG_ICM_WHOAMI, &rval, 1) ||
118  rval != ICM_WHOAMI_VAL) {
119  // not an ICM_WHOAMI
120  goto fail;
121  }
122  // see if ICM20948 is sleeping
123  if (!dev_icm->read_registers(REG_ICM_PWR_MGMT_1, &rval, 1)) {
124  goto fail;
125  }
126  if (rval & 0x40) {
127  // bring out of sleep mode, use internal oscillator
129  hal.scheduler->delay(10);
130  }
131  // enable i2c bypass
133  }
134 
135  uint16_t whoami;
136  if (!dev->read_registers(REG_COMPANY_ID, (uint8_t *)&whoami, 2) ||
137  whoami != 0x0948) {
138  // not a AK09916
139  goto fail;
140  }
141 
143 
144  dev->write_register(REG_CNTL2, 0x08, true); // continuous 100Hz
145  dev->write_register(REG_CNTL3, 0x00, true);
146 
147  dev->get_semaphore()->give();
148 
149  /* register the compass instance in the frontend */
151 
152  printf("Found a AK09916 on 0x%x as compass %u\n", dev->get_bus_id(), compass_instance);
153 
155 
156  if (force_external) {
158  }
159 
162 
163  // call timer() at 100Hz
166 
167  return true;
168 
169 fail:
170  dev->get_semaphore()->give();
171  return false;
172 }
173 
175 {
176  struct PACKED {
177  int16_t magx;
178  int16_t magy;
179  int16_t magz;
180  uint8_t tmps;
181  uint8_t status2;
182  } data;
183  const float to_utesla = 4912.0f / 32752.0f;
184  const float utesla_to_milliGauss = 10;
185  const float range_scale = to_utesla * utesla_to_milliGauss;
186  Vector3f field;
187 
188  // check data ready
189  uint8_t st1;
190  if (!dev->read_registers(REG_ST1, &st1, 1) || !(st1 & 1)) {
191  goto check_registers;
192  }
193 
194  if (!dev->read_registers(REG_HXL, (uint8_t *)&data, sizeof(data))) {
195  goto check_registers;
196  }
197 
198  field(data.magx * range_scale, data.magy * range_scale, data.magz * range_scale);
199 
200  /* rotate raw_field from sensor frame to body frame */
202 
203  /* publish raw_field (uncorrected point sample) for calibration use */
205 
206  /* correct raw_field for known errors */
208 
210  accum += field;
211  accum_count++;
212  _sem->give();
213  }
214 
215 check_registers:
217 }
218 
220 {
221  if (!_sem->take_nonblocking()) {
222  return;
223  }
224  if (accum_count == 0) {
225  _sem->give();
226  return;
227  }
228 
229  accum /= accum_count;
230 
232 
233  accum.zero();
234  accum_count = 0;
235 
236  _sem->give();
237 }
#define REG_ST1
int printf(const char *fmt,...)
Definition: stdio.c:113
AP_HAL::OwnPtr< AP_HAL::Device > dev_icm
void set_external(uint8_t instance, bool external)
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
uint32_t get_bus_id(void) const
Definition: Device.h:60
#define ICM_WHOAMI_VAL
virtual AP_HAL::Semaphore * get_semaphore()=0
void rotate_field(Vector3f &mag, uint8_t instance)
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
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
AP_HAL::OwnPtr< AP_HAL::Device > dev
void set_dev_id(uint8_t instance, uint32_t dev_id)
Rotation
Definition: rotations.h:27
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
bool setup_checked_registers(uint8_t num_regs, uint8_t frequency=10)
Definition: Device.cpp:39
void fail(const char *why)
Definition: eedump.c:28
virtual void delay(uint16_t ms)=0
#define REG_HXL
void set_device_type(uint8_t devtype)
Definition: Device.h:70
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
virtual bool take_nonblocking() WARN_IF_UNUSED=0
enum Rotation rotation
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
uint8_t register_compass(void) const
#define REG_COMPANY_ID
AP_Compass_AK09916(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, AP_HAL::OwnPtr< AP_HAL::Device > dev_icm, bool force_external, enum Rotation rotation, enum bus_type bus_type)
virtual bool give()=0
static Compass compass
Definition: AHRS_Test.cpp:20
AP_HAL::Semaphore * _sem
#define REG_ICM_PWR_MGMT_1
#define REG_CNTL3
void set_rotation(uint8_t instance, enum Rotation rotation)
bool check_next_register(void)
Definition: Device.cpp:85
#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
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
void publish_raw_field(const Vector3f &mag, uint8_t instance)
#define REG_ICM_INT_PIN_CFG
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
#define REG_CNTL2
void zero()
Definition: vector3.h:182
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
#define REG_ICM_WHOAMI
static AP_Compass_Backend * probe_ICM20948(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev_icm, bool force_external=false, enum Rotation rotation=ROTATION_NONE)