APM:Libraries
AP_Compass_LSM303D.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 <utility>
16 
17 #include <AP_HAL/AP_HAL.h>
18 #include <AP_Math/AP_Math.h>
19 
20 #include "AP_Compass_LSM303D.h"
21 
22 extern const AP_HAL::HAL &hal;
23 
24 #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
25 #include <AP_HAL_Linux/GPIO.h>
26 #endif
27 
28 #ifndef LSM303D_DRDY_M_PIN
29 #define LSM303D_DRDY_M_PIN -1
30 #endif
31 
32 /* SPI protocol address bits */
33 #define DIR_READ (1<<7)
34 #define DIR_WRITE (0<<7)
35 #define ADDR_INCREMENT (1<<6)
36 
37 /* register addresses: A: accel, M: mag, T: temp */
38 #define ADDR_WHO_AM_I 0x0F
39 #define WHO_I_AM 0x49
40 
41 #define ADDR_OUT_TEMP_L 0x05
42 #define ADDR_OUT_TEMP_H 0x06
43 #define ADDR_STATUS_M 0x07
44 #define ADDR_OUT_X_L_M 0x08
45 #define ADDR_OUT_X_H_M 0x09
46 #define ADDR_OUT_Y_L_M 0x0A
47 #define ADDR_OUT_Y_H_M 0x0B
48 #define ADDR_OUT_Z_L_M 0x0C
49 #define ADDR_OUT_Z_H_M 0x0D
50 
51 #define ADDR_INT_CTRL_M 0x12
52 #define ADDR_INT_SRC_M 0x13
53 #define ADDR_REFERENCE_X 0x1c
54 #define ADDR_REFERENCE_Y 0x1d
55 #define ADDR_REFERENCE_Z 0x1e
56 
57 #define ADDR_STATUS_A 0x27
58 #define ADDR_OUT_X_L_A 0x28
59 #define ADDR_OUT_X_H_A 0x29
60 #define ADDR_OUT_Y_L_A 0x2A
61 #define ADDR_OUT_Y_H_A 0x2B
62 #define ADDR_OUT_Z_L_A 0x2C
63 #define ADDR_OUT_Z_H_A 0x2D
64 
65 #define ADDR_CTRL_REG0 0x1F
66 #define ADDR_CTRL_REG1 0x20
67 #define ADDR_CTRL_REG2 0x21
68 #define ADDR_CTRL_REG3 0x22
69 #define ADDR_CTRL_REG4 0x23
70 #define ADDR_CTRL_REG5 0x24
71 #define ADDR_CTRL_REG6 0x25
72 #define ADDR_CTRL_REG7 0x26
73 
74 #define ADDR_FIFO_CTRL 0x2e
75 #define ADDR_FIFO_SRC 0x2f
76 
77 #define ADDR_IG_CFG1 0x30
78 #define ADDR_IG_SRC1 0x31
79 #define ADDR_IG_THS1 0x32
80 #define ADDR_IG_DUR1 0x33
81 #define ADDR_IG_CFG2 0x34
82 #define ADDR_IG_SRC2 0x35
83 #define ADDR_IG_THS2 0x36
84 #define ADDR_IG_DUR2 0x37
85 #define ADDR_CLICK_CFG 0x38
86 #define ADDR_CLICK_SRC 0x39
87 #define ADDR_CLICK_THS 0x3a
88 #define ADDR_TIME_LIMIT 0x3b
89 #define ADDR_TIME_LATENCY 0x3c
90 #define ADDR_TIME_WINDOW 0x3d
91 #define ADDR_ACT_THS 0x3e
92 #define ADDR_ACT_DUR 0x3f
93 
94 #define REG1_RATE_BITS_A ((1<<7) | (1<<6) | (1<<5) | (1<<4))
95 #define REG1_POWERDOWN_A ((0<<7) | (0<<6) | (0<<5) | (0<<4))
96 #define REG1_RATE_3_125HZ_A ((0<<7) | (0<<6) | (0<<5) | (1<<4))
97 #define REG1_RATE_6_25HZ_A ((0<<7) | (0<<6) | (1<<5) | (0<<4))
98 #define REG1_RATE_12_5HZ_A ((0<<7) | (0<<6) | (1<<5) | (1<<4))
99 #define REG1_RATE_25HZ_A ((0<<7) | (1<<6) | (0<<5) | (0<<4))
100 #define REG1_RATE_50HZ_A ((0<<7) | (1<<6) | (0<<5) | (1<<4))
101 #define REG1_RATE_100HZ_A ((0<<7) | (1<<6) | (1<<5) | (0<<4))
102 #define REG1_RATE_200HZ_A ((0<<7) | (1<<6) | (1<<5) | (1<<4))
103 #define REG1_RATE_400HZ_A ((1<<7) | (0<<6) | (0<<5) | (0<<4))
104 #define REG1_RATE_800HZ_A ((1<<7) | (0<<6) | (0<<5) | (1<<4))
105 #define REG1_RATE_1600HZ_A ((1<<7) | (0<<6) | (1<<5) | (0<<4))
106 
107 #define REG1_BDU_UPDATE (1<<3)
108 #define REG1_Z_ENABLE_A (1<<2)
109 #define REG1_Y_ENABLE_A (1<<1)
110 #define REG1_X_ENABLE_A (1<<0)
111 
112 #define REG2_ANTIALIAS_FILTER_BW_BITS_A ((1<<7) | (1<<6))
113 #define REG2_AA_FILTER_BW_773HZ_A ((0<<7) | (0<<6))
114 #define REG2_AA_FILTER_BW_194HZ_A ((0<<7) | (1<<6))
115 #define REG2_AA_FILTER_BW_362HZ_A ((1<<7) | (0<<6))
116 #define REG2_AA_FILTER_BW_50HZ_A ((1<<7) | (1<<6))
117 
118 #define REG2_FULL_SCALE_BITS_A ((1<<5) | (1<<4) | (1<<3))
119 #define REG2_FULL_SCALE_2G_A ((0<<5) | (0<<4) | (0<<3))
120 #define REG2_FULL_SCALE_4G_A ((0<<5) | (0<<4) | (1<<3))
121 #define REG2_FULL_SCALE_6G_A ((0<<5) | (1<<4) | (0<<3))
122 #define REG2_FULL_SCALE_8G_A ((0<<5) | (1<<4) | (1<<3))
123 #define REG2_FULL_SCALE_16G_A ((1<<5) | (0<<4) | (0<<3))
124 
125 #define REG5_ENABLE_T (1<<7)
126 
127 #define REG5_RES_HIGH_M ((1<<6) | (1<<5))
128 #define REG5_RES_LOW_M ((0<<6) | (0<<5))
129 
130 #define REG5_RATE_BITS_M ((1<<4) | (1<<3) | (1<<2))
131 #define REG5_RATE_3_125HZ_M ((0<<4) | (0<<3) | (0<<2))
132 #define REG5_RATE_6_25HZ_M ((0<<4) | (0<<3) | (1<<2))
133 #define REG5_RATE_12_5HZ_M ((0<<4) | (1<<3) | (0<<2))
134 #define REG5_RATE_25HZ_M ((0<<4) | (1<<3) | (1<<2))
135 #define REG5_RATE_50HZ_M ((1<<4) | (0<<3) | (0<<2))
136 #define REG5_RATE_100HZ_M ((1<<4) | (0<<3) | (1<<2))
137 #define REG5_RATE_DO_NOT_USE_M ((1<<4) | (1<<3) | (0<<2))
138 
139 #define REG6_FULL_SCALE_BITS_M ((1<<6) | (1<<5))
140 #define REG6_FULL_SCALE_2GA_M ((0<<6) | (0<<5))
141 #define REG6_FULL_SCALE_4GA_M ((0<<6) | (1<<5))
142 #define REG6_FULL_SCALE_8GA_M ((1<<6) | (0<<5))
143 #define REG6_FULL_SCALE_12GA_M ((1<<6) | (1<<5))
144 
145 #define REG7_CONT_MODE_M ((0<<1) | (0<<0))
146 
147 #define INT_CTRL_M 0x12
148 #define INT_SRC_M 0x13
149 
150 #define LSM303D_MAG_DEFAULT_RANGE_GA 2
151 #define LSM303D_MAG_DEFAULT_RATE 100
152 
154  : AP_Compass_Backend(compass)
155  , _dev(std::move(dev))
156 {
157 }
158 
161  enum Rotation rotation)
162 {
163  if (!dev) {
164  return nullptr;
165  }
166  AP_Compass_LSM303D *sensor = new AP_Compass_LSM303D(compass, std::move(dev));
167  if (!sensor || !sensor->init(rotation)) {
168  delete sensor;
169  return nullptr;
170  }
171 
172  return sensor;
173 }
174 
176 {
177  uint8_t val = 0;
178 
179  reg |= DIR_READ;
180  _dev->read_registers(reg, &val, 1);
181 
182  return val;
183 }
184 
185 bool AP_Compass_LSM303D::_block_read(uint8_t reg, uint8_t *buf, uint32_t size)
186 {
187  reg |= DIR_READ | ADDR_INCREMENT;
188  return _dev->read_registers(reg, buf, size);
189 }
190 
191 void AP_Compass_LSM303D::_register_write(uint8_t reg, uint8_t val)
192 {
193  _dev->write_register(reg, val);
194 }
195 
196 void AP_Compass_LSM303D::_register_modify(uint8_t reg, uint8_t clearbits, uint8_t setbits)
197 {
198  uint8_t val;
199 
200  val = _register_read(reg);
201  val &= ~clearbits;
202  val |= setbits;
203  _register_write(reg, val);
204 }
205 
211 {
212  return _drdy_pin_m == nullptr || (_drdy_pin_m->read() != 0);
213 }
214 
215 
216 // Read Sensor data
218 {
219  struct PACKED {
220  uint8_t status;
221  int16_t x;
222  int16_t y;
223  int16_t z;
224  } rx;
225 
227  hal.console->printf("LSM303D _read_data_transaction_accel: _reg7_expected unexpected\n");
228  return false;
229  }
230 
231  if (!_data_ready()) {
232  return false;
233  }
234 
235  if (!_block_read(ADDR_STATUS_M, (uint8_t *) &rx, sizeof(rx))) {
236  return false;
237  }
238 
239  /* check for overrun */
240  if ((rx.status & 0x70) != 0) {
241  return false;
242  }
243 
244  if (rx.x == 0 && rx.y == 0 && rx.z == 0) {
245  return false;
246  }
247 
248  _mag_x = rx.x;
249  _mag_y = rx.y;
250  _mag_z = rx.z;
251 
252  return true;
253 }
254 
256 {
257  if (LSM303D_DRDY_M_PIN >= 0) {
260  }
261 
262  bool success = _hardware_init();
263 
264  if (!success) {
265  return false;
266  }
267 
268  _initialised = true;
269 
270  /* register the compass instance in the frontend */
272 
273  set_rotation(_compass_instance, rotation);
274 
277 
278  // read at 100Hz
280 
281  return true;
282 }
283 
285 {
287  AP_HAL::panic("LSM303D: Unable to get semaphore");
288  }
289 
290  // initially run the bus at low speed
292 
293  // Test WHOAMI
294  uint8_t whoami = _register_read(ADDR_WHO_AM_I);
295  if (whoami != WHO_I_AM) {
296  hal.console->printf("LSM303D: unexpected WHOAMI 0x%x\n", (unsigned)whoami);
297  goto fail_whoami;
298  }
299 
300  uint8_t tries;
301  for (tries = 0; tries < 5; tries++) {
302  // ensure the chip doesn't interpret any other bus traffic as I2C
303  _disable_i2c();
304 
305  /* enable mag */
309 
310  // DRDY on MAG on INT2
312 
315 
316  hal.scheduler->delay(10);
317  if (_data_ready()) {
318  break;
319  }
320  }
321  if (tries == 5) {
322  hal.console->printf("Failed to boot LSM303D 5 times\n");
323  goto fail_tries;
324  }
325 
327  _dev->get_semaphore()->give();
328 
329  return true;
330 
331 fail_tries:
332 fail_whoami:
333  _dev->get_semaphore()->give();
335  return false;
336 }
337 
339 {
340  if (!_read_sample()) {
341  return;
342  }
343 
345 
346  // rotate raw_field from sensor frame to body frame
347  rotate_field(raw_field, _compass_instance);
348 
349  // publish raw_field (uncorrected point sample) for calibration use
351 
352  // correct raw_field for known errors
353  correct_field(raw_field, _compass_instance);
354 
356  _mag_x_accum += raw_field.x;
357  _mag_y_accum += raw_field.y;
358  _mag_z_accum += raw_field.z;
359  _accum_count++;
360  if (_accum_count == 10) {
361  _mag_x_accum /= 2;
362  _mag_y_accum /= 2;
363  _mag_z_accum /= 2;
364  _accum_count = 5;
365  }
366  _sem->give();
367  }
368 }
369 
370 // Read Sensor data
372 {
373  if (!_initialised) {
374  return;
375  }
376 
377  if (!_sem->take_nonblocking()) {
378  return;
379  }
380 
381  if (_accum_count == 0) {
382  /* We're not ready to publish*/
383  _sem->give();
384  return;
385  }
386 
388  field /= _accum_count;
389 
390  _accum_count = 0;
392 
393  _sem->give();
394 
396 }
397 
399 {
400  // TODO: use the register names
401  uint8_t a = _register_read(0x02);
402  _register_write(0x02, (0x10 | a));
403  a = _register_read(0x02);
404  _register_write(0x02, (0xF7 & a));
405  a = _register_read(0x15);
406  _register_write(0x15, (0x80 | a));
407  a = _register_read(0x02);
408  _register_write(0x02, (0xE7 & a));
409 }
410 
412 {
413  uint8_t setbits = 0;
414  uint8_t clearbits = REG6_FULL_SCALE_BITS_M;
415  float new_scale_ga_digit = 0.0f;
416 
417  if (max_ga == 0) {
418  max_ga = 12;
419  }
420 
421  if (max_ga <= 2) {
422  _mag_range_ga = 2;
423  setbits |= REG6_FULL_SCALE_2GA_M;
424  new_scale_ga_digit = 0.080f;
425  } else if (max_ga <= 4) {
426  _mag_range_ga = 4;
427  setbits |= REG6_FULL_SCALE_4GA_M;
428  new_scale_ga_digit = 0.160f;
429  } else if (max_ga <= 8) {
430  _mag_range_ga = 8;
431  setbits |= REG6_FULL_SCALE_8GA_M;
432  new_scale_ga_digit = 0.320f;
433  } else if (max_ga <= 12) {
434  _mag_range_ga = 12;
435  setbits |= REG6_FULL_SCALE_12GA_M;
436  new_scale_ga_digit = 0.479f;
437  } else {
438  return false;
439  }
440 
441  _mag_range_scale = new_scale_ga_digit;
442  _register_modify(ADDR_CTRL_REG6, clearbits, setbits);
443 
444  return true;
445 }
446 
448 {
449  uint8_t setbits = 0;
450  uint8_t clearbits = REG5_RATE_BITS_M;
451 
452  if (frequency == 0) {
453  frequency = 100;
454  }
455 
456  if (frequency <= 25) {
457  setbits |= REG5_RATE_25HZ_M;
458  _mag_samplerate = 25;
459  } else if (frequency <= 50) {
460  setbits |= REG5_RATE_50HZ_M;
461  _mag_samplerate = 50;
462  } else if (frequency <= 100) {
463  setbits |= REG5_RATE_100HZ_M;
464  _mag_samplerate = 100;
465  } else {
466  return false;
467  }
468 
469  _register_modify(ADDR_CTRL_REG5, clearbits, setbits);
470 
471  return true;
472 }
#define REG6_FULL_SCALE_12GA_M
#define REG5_RATE_BITS_M
AP_HAL::OwnPtr< AP_HAL::Device > _dev
#define REG5_RATE_25HZ_M
Vector3< float > Vector3f
Definition: vector3.h:246
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation=ROTATION_NONE)
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
#define ADDR_WHO_AM_I
AP_HAL::UARTDriver * console
Definition: HAL.h:110
uint32_t get_bus_id(void) const
Definition: Device.h:60
void _register_write(uint8_t reg, uint8_t val)
uint8_t _register_read(uint8_t reg)
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)
#define REG6_FULL_SCALE_4GA_M
void correct_field(Vector3f &mag, uint8_t i)
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
#define REG5_RATE_100HZ_M
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
AP_Compass_LSM303D(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev)
#define REG6_FULL_SCALE_8GA_M
#define LSM303D_MAG_DEFAULT_RANGE_GA
void set_dev_id(uint8_t instance, uint32_t dev_id)
#define REG7_CONT_MODE_M
Rotation
Definition: rotations.h:27
#define ADDR_INCREMENT
#define ADDR_CTRL_REG4
virtual void mode(uint8_t output)=0
#define ADDR_CTRL_REG5
virtual void delay(uint16_t ms)=0
void _register_modify(uint8_t reg, uint8_t clearbits, uint8_t setbits)
void set_device_type(uint8_t devtype)
Definition: Device.h:70
bool _mag_set_samplerate(uint16_t frequency)
#define x(i)
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size)
#define WHO_I_AM
virtual bool take_nonblocking() WARN_IF_UNUSED=0
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
uint8_t register_compass(void) const
virtual bool set_speed(Speed speed)=0
T y
Definition: vector3.h:67
virtual AP_HAL::DigitalSource * channel(uint16_t n)=0
T z
Definition: vector3.h:67
#define DIR_READ
#define REG6_FULL_SCALE_2GA_M
virtual bool give()=0
static Compass compass
Definition: AHRS_Test.cpp:20
#define LSM303D_DRDY_M_PIN
AP_HAL::Semaphore * _sem
bool init(enum Rotation rotation)
#define HAL_GPIO_INPUT
Definition: GPIO.h:7
#define ADDR_STATUS_M
#define REG5_RES_HIGH_M
#define LSM303D_MAG_DEFAULT_RATE
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
virtual uint8_t read()=0
AP_HAL::GPIO * gpio
Definition: HAL.h:111
void set_rotation(uint8_t instance, enum Rotation rotation)
AP_HAL::DigitalSource * _drdy_pin_m
#define PACKED
Definition: AP_Common.h:28
#define ADDR_CTRL_REG6
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
#define REG5_RATE_50HZ_M
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
#define ADDR_CTRL_REG7
void publish_raw_field(const Vector3f &mag, uint8_t instance)
#define REG6_FULL_SCALE_BITS_M
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
T x
Definition: vector3.h:67
bool _mag_set_range(uint8_t max_ga)