APM:Libraries
AP_Compass_BMM150.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016 Intel Corporation. All rights reserved.
3  *
4  * This file is free software: you can redistribute it and/or modify it
5  * under the terms of the GNU General Public License as published by the
6  * Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * This file is distributed in the hope that it will be useful, but
10  * WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12  * See the GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License along
15  * with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 #include "AP_Compass_BMM150.h"
18 
19 #include <AP_HAL/AP_HAL.h>
20 
21 #include <utility>
22 
24 #include <AP_Math/AP_Math.h>
25 #include <stdio.h>
26 
27 #define CHIP_ID_REG 0x40
28 #define CHIP_ID_VAL 0x32
29 
30 #define POWER_AND_OPERATIONS_REG 0x4B
31 #define POWER_CONTROL_VAL (1 << 0)
32 #define SOFT_RESET (1 << 7 | 1 << 1)
33 
34 #define OP_MODE_SELF_TEST_ODR_REG 0x4C
35 #define NORMAL_MODE (0 << 1)
36 #define ODR_30HZ (1 << 3 | 1 << 4 | 1 << 5)
37 #define ODR_20HZ (1 << 3 | 0 << 4 | 1 << 5)
38 
39 #define DATA_X_LSB_REG 0x42
40 
41 #define REPETITIONS_XY_REG 0x51
42 #define REPETITIONS_Z_REG 0X52
43 
44 /* Trim registers */
45 #define DIG_X1_REG 0x5D
46 #define DIG_Y1_REG 0x5E
47 #define DIG_Z4_LSB_REG 0x62
48 #define DIG_Z4_MSB_REG 0x63
49 #define DIG_X2_REG 0x64
50 #define DIG_Y2_REG 0x65
51 #define DIG_Z2_LSB_REG 0x68
52 #define DIG_Z2_MSB_REG 0x69
53 #define DIG_Z1_LSB_REG 0x6A
54 #define DIG_Z1_MSB_REG 0x6B
55 #define DIG_XYZ1_LSB_REG 0x6C
56 #define DIG_XYZ1_MSB_REG 0x6D
57 #define DIG_Z3_LSB_REG 0x6E
58 #define DIG_Z3_MSB_REG 0x6F
59 #define DIG_XY2_REG 0x70
60 #define DIG_XY1_REG 0x71
61 
62 #define MEASURE_TIME_USEC 16667
63 
64 extern const AP_HAL::HAL &hal;
65 
68 {
69  if (!dev) {
70  return nullptr;
71  }
72  AP_Compass_BMM150 *sensor = new AP_Compass_BMM150(compass, std::move(dev));
73  if (!sensor || !sensor->init()) {
74  delete sensor;
75  return nullptr;
76  }
77 
78  return sensor;
79 }
80 
83  : AP_Compass_Backend(compass)
84  , _dev(std::move(dev))
85 {
86 }
87 
89 {
90  struct {
91  int8_t dig_x1;
92  int8_t dig_y1;
93  uint8_t rsv[3];
94  le16_t dig_z4;
95  int8_t dig_x2;
96  int8_t dig_y2;
97  uint8_t rsv2[2];
98  le16_t dig_z2;
99  le16_t dig_z1;
100  le16_t dig_xyz1;
101  le16_t dig_z3;
102  int8_t dig_xy2;
103  uint8_t dig_xy1;
104  } PACKED trim_registers, trim_registers2;
105 
106  // read the registers twice to confirm we have the right
107  // values. There is no CRC in the registers and these values are
108  // vital to correct operation
109  int8_t tries = 4;
110  while (tries--) {
111  if (!_dev->read_registers(DIG_X1_REG, (uint8_t *)&trim_registers,
112  sizeof(trim_registers))) {
113  continue;
114  }
115  if (!_dev->read_registers(DIG_X1_REG, (uint8_t *)&trim_registers2,
116  sizeof(trim_registers))) {
117  continue;
118  }
119  if (memcmp(&trim_registers, &trim_registers2, sizeof(trim_registers)) == 0) {
120  break;
121  }
122  }
123  if (-1 == tries) {
124  hal.console->printf("BMM150: Failed to load trim registers\n");
125  return false;
126  }
127 
128  _dig.x1 = trim_registers.dig_x1;
129  _dig.x2 = trim_registers.dig_x2;
130  _dig.xy1 = trim_registers.dig_xy1;
131  _dig.xy2 = trim_registers.dig_xy2;
132  _dig.xyz1 = le16toh(trim_registers.dig_xyz1);
133  _dig.y1 = trim_registers.dig_y1;
134  _dig.y2 = trim_registers.dig_y2;
135  _dig.z1 = le16toh(trim_registers.dig_z1);
136  _dig.z2 = le16toh(trim_registers.dig_z2);
137  _dig.z3 = le16toh(trim_registers.dig_z3);
138  _dig.z4 = le16toh(trim_registers.dig_z4);
139 
140  return true;
141 }
142 
144 {
145  uint8_t val = 0;
146  bool ret;
147 
149  hal.console->printf("BMM150: Unable to get bus semaphore\n");
150  return false;
151  }
152 
153  // 10 retries for init
154  _dev->set_retries(10);
155 
156  // use checked registers to cope with bus errors
158 
159  int8_t boot_tries = 4;
160  while (boot_tries--) {
161  /* Do a soft reset */
163  hal.scheduler->delay(2);
164  if (!ret) {
165  continue;
166  }
167 
168  /* Change power state from suspend mode to sleep mode */
170  hal.scheduler->delay(2);
171  if (!ret) {
172  continue;
173  }
174 
175  ret = _dev->read_registers(CHIP_ID_REG, &val, 1);
176  if (!ret) {
177  continue;
178  }
179  if (val == CHIP_ID_VAL) {
180  // found it
181  break;
182  }
183  if (boot_tries == 0) {
184  hal.console->printf("BMM150: Wrong chip ID 0x%02x should be 0x%02x\n", val, CHIP_ID_VAL);
185  }
186  }
187  if (-1 == boot_tries) {
188  goto bus_error;
189  }
190 
191  ret = _load_trim_values();
192  if (!ret) {
193  goto bus_error;
194  }
195 
196  /*
197  * Recommended preset for high accuracy:
198  * - Rep X/Y = 47
199  * - Rep Z = 83
200  * - ODR = 20
201  * But we are going to use 30Hz of ODR
202  */
203  ret = _dev->write_register(REPETITIONS_XY_REG, (47 - 1) / 2, true);
204  if (!ret) {
205  goto bus_error;
206  }
207  ret = _dev->write_register(REPETITIONS_Z_REG, 83 - 1, true);
208  if (!ret) {
209  goto bus_error;
210  }
211  /* Change operation mode from sleep to normal and set ODR */
213  if (!ret) {
214  goto bus_error;
215  }
216 
217  _dev->get_semaphore()->give();
218 
219  /* register the compass instance in the frontend */
221 
224 
225  _perf_err = hal.util->perf_alloc(AP_HAL::Util::PC_COUNT, "BMM150_err");
226 
227  // 2 retries for run
228  _dev->set_retries(2);
229 
232 
234 
235  return true;
236 
237 bus_error:
238  hal.console->printf("BMM150: Bus communication error\n");
239  _dev->get_semaphore()->give();
240  return false;
241 }
242 
243 /*
244  * Compensation algorithm got from https://github.com/BoschSensortec/BMM050_driver
245  * this is not explained in datasheet.
246  */
247 int16_t AP_Compass_BMM150::_compensate_xy(int16_t xy, uint32_t rhall, int32_t txy1, int32_t txy2)
248 {
249  int32_t inter = ((int32_t)_dig.xyz1) << 14;
250  inter /= rhall;
251  inter -= 0x4000;
252 
253  int32_t val = _dig.xy2 * ((inter * inter) >> 7);
254  val += (inter * (((uint32_t)_dig.xy1) << 7));
255  val >>= 9;
256  val += 0x100000;
257  val *= (txy2 + 0xA0);
258  val >>= 12;
259  val *= xy;
260  val >>= 13;
261  val += (txy1 << 3);
262 
263  return val;
264 }
265 
266 int16_t AP_Compass_BMM150::_compensate_z(int16_t z, uint32_t rhall)
267 {
268  int32_t dividend = int32_t(z - _dig.z4) << 15;
269  int32_t dividend2 = dividend - ((_dig.z3 * (int32_t(rhall) - int32_t(_dig.xyz1))) >> 2);
270 
271  int32_t divisor = int32_t(_dig.z1) * (rhall << 1);
272  divisor += 0x8000;
273  divisor >>= 16;
274  divisor += _dig.z2;
275 
276  int16_t ret = constrain_int32(dividend2 / divisor, -0x8000, 0x8000);
277 #if 0
278  static uint8_t counter;
279  if (counter++ == 0) {
280  printf("ret=%d z=%d rhall=%u z1=%d z2=%d z3=%d z4=%d xyz1=%d dividend=%d dividend2=%d divisor=%d\n",
281  ret, z, rhall, _dig.z1, _dig.z2, _dig.z3, _dig.z4, _dig.xyz1, dividend, dividend2, divisor);
282  }
283 #endif
284  return ret;
285 }
286 
288 {
289  le16_t data[4];
290  bool ret = _dev->read_registers(DATA_X_LSB_REG, (uint8_t *) &data, sizeof(data));
291 
292  /* Checking data ready status */
293  if (!ret || !(data[3] & 0x1)) {
295  uint32_t now = AP_HAL::millis();
296  if (now - _last_read_ms > 250) {
297  // cope with power cycle to sensor
298  _last_read_ms = now;
301  hal.util->perf_count(_perf_err);
302  }
303  return;
304  }
305 
306  const uint16_t rhall = le16toh(data[3]) >> 2;
307 
308  Vector3f raw_field = Vector3f{
309  (float) _compensate_xy(((int16_t)le16toh(data[0])) >> 3,
310  rhall, _dig.x1, _dig.x2),
311  (float) _compensate_xy(((int16_t)le16toh(data[1])) >> 3,
312  rhall, _dig.y1, _dig.y2),
313  (float) _compensate_z(((int16_t)le16toh(data[2])) >> 1, rhall)};
314 
315  /* apply sensitivity scale 16 LSB/uT */
316  raw_field /= 16;
317  /* convert uT to milligauss */
318  raw_field *= 10;
319 
320  /* rotate raw_field from sensor frame to body frame */
321  rotate_field(raw_field, _compass_instance);
322 
323  /* publish raw_field (uncorrected point sample) for calibration use */
325 
326  /* correct raw_field for known errors */
327  correct_field(raw_field, _compass_instance);
328 
330 
332  return;
333  }
334  _mag_accum += raw_field;
335  _accum_count++;
336  if (_accum_count == 10) {
337  _mag_accum /= 2;
338  _accum_count = 5;
339  }
340  _sem->give();
341 
343 }
344 
346 {
347  if (!_sem->take_nonblocking()) {
348  return;
349  }
350  if (_accum_count == 0) {
351  _sem->give();
352  return;
353  }
354 
355  Vector3f field(_mag_accum);
356  field /= _accum_count;
357  _mag_accum.zero();
358  _accum_count = 0;
359  _sem->give();
360 
362 }
363 
int printf(const char *fmt,...)
Definition: stdio.c:113
static uint8_t counter
#define DATA_X_LSB_REG
virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name)
Definition: Util.h:102
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
#define SOFT_RESET
AP_HAL::UARTDriver * console
Definition: HAL.h:110
uint32_t get_bus_id(void) const
Definition: Device.h:60
#define NORMAL_MODE
virtual AP_HAL::Semaphore * get_semaphore()=0
void rotate_field(Vector3f &mag, uint8_t instance)
virtual void set_retries(uint8_t retries)
Definition: Device.h:260
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
AP_Compass_BMM150(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev)
#define POWER_AND_OPERATIONS_REG
void correct_field(Vector3f &mag, uint8_t i)
#define DIG_X1_REG
AP_HAL::Util * util
Definition: HAL.h:115
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
int16_t _compensate_xy(int16_t xy, uint32_t rhall, int32_t txy1, int32_t txy2)
int16_t _compensate_z(int16_t z, uint32_t rhall)
#define POWER_CONTROL_VAL
void set_dev_id(uint8_t instance, uint32_t dev_id)
struct AP_Compass_BMM150::@18 _dig
#define CHIP_ID_REG
bool setup_checked_registers(uint8_t num_regs, uint8_t frequency=10)
Definition: Device.cpp:39
#define ODR_30HZ
virtual void delay(uint16_t ms)=0
void set_device_type(uint8_t devtype)
Definition: Device.h:70
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
AP_HAL::OwnPtr< AP_HAL::Device > _dev
virtual bool take_nonblocking() WARN_IF_UNUSED=0
void read() override
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
uint8_t register_compass(void) const
#define MEASURE_TIME_USEC
int32_t constrain_int32(const int32_t amt, const int32_t low, const int32_t high)
Definition: AP_Math.h:152
#define CHIP_ID_VAL
uint32_t millis()
Definition: system.cpp:157
AP_HAL::Util::perf_counter_t _perf_err
virtual bool give()=0
static Compass compass
Definition: AHRS_Test.cpp:20
uint16_t __ap_bitwise le16_t
Definition: sparse-endian.h:35
AP_HAL::Semaphore * _sem
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define REPETITIONS_Z_REG
#define OP_MODE_SELF_TEST_ODR_REG
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 REPETITIONS_XY_REG
static uint16_t le16toh(le16_t value)
Definition: sparse-endian.h:79
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
void zero()
Definition: vector3.h:182
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
virtual void perf_count(perf_counter_t h)
Definition: Util.h:105