APM:Libraries
AP_Compass_LSM9DS1.cpp
Go to the documentation of this file.
1 
2 #include <assert.h>
3 #include <utility>
4 
5 #include <AP_Math/AP_Math.h>
6 #include <AP_HAL/AP_HAL.h>
7 
8 #include "AP_Compass_LSM9DS1.h"
9 
10 
11 #define LSM9DS1M_OFFSET_X_REG_L_M 0x05
12 #define LSM9DS1M_OFFSET_X_REG_H_M 0x06
13 #define LSM9DS1M_OFFSET_Y_REG_L_M 0x07
14 #define LSM9DS1M_OFFSET_Y_REG_H_M 0x08
15 #define LSM9DS1M_OFFSET_Z_REG_L_M 0x09
16 #define LSM9DS1M_OFFSET_Z_REG_H_M 0x0A
17 
18 #define LSM9DS1M_WHO_AM_I 0x0F
19  #define WHO_AM_I_MAG 0x3D
20 
21 #define LSM9DS1M_CTRL_REG1_M 0x20
22  #define LSM9DS1M_TEMP_COMP (0x1 << 7)
23  #define LSM9DS1M_XY_ULTRA_HIGH (0x3 << 5)
24  #define LSM9DS1M_80HZ (0x7 << 2)
25  #define LSM9DS1M_FAST_ODR (0x1 << 1)
26 
27 #define LSM9DS1M_CTRL_REG2_M 0x21
28  #define LSM9DS1M_FS_16G (0x3 << 5)
29 
30 #define LSM9DS1M_CTRL_REG3_M 0x22
31  #define LSM9DS1M_SPI_ENABLE (0x01 << 2)
32  #define LSM9DS1M_CONTINUOUS_MODE 0x0
33 
34 #define LSM9DS1M_CTRL_REG4_M 0x23
35  #define LSM9DS1M_Z_ULTRA_HIGH (0x3 << 2)
36 
37 #define LSM9DS1M_CTRL_REG5_M 0x24
38  #define LSM9DS1M_BDU (0x0 << 6)
39 
40 #define LSM9DS1M_STATUS_REG_M 0x27
41 
42 #define LSM9DS1M_OUT_X_L_M 0x28
43 #define LSM9DS1M_OUT_X_H_M 0x29
44 #define LSM9DS1M_OUT_Y_L_M 0x2A
45 #define LSM9DS1M_OUT_Y_H_M 0x2B
46 #define LSM9DS1M_OUT_Z_L_M 0x2C
47 #define LSM9DS1M_OUT_Z_H_M 0x2D
48 #define LSM9DS1M_INT_CFG_M 0x30
49 #define LSM9DS1M_INT_SRC_M 0x31
50 #define LSM9DS1M_INT_THS_L_M 0x32
51 #define LSM9DS1M_INT_THS_H_M 0x33
52 
53 struct PACKED sample_regs {
54  uint8_t status;
55  int16_t val[3];
56 };
57 
58 extern const AP_HAL::HAL &hal;
59 
62  enum Rotation rotation)
63  : AP_Compass_Backend(compass)
64  , _dev(std::move(dev))
65  , _rotation(rotation)
66 {
67 }
68 
71  enum Rotation rotation)
72 {
73  if (!dev) {
74  return nullptr;
75  }
76  AP_Compass_LSM9DS1 *sensor = new AP_Compass_LSM9DS1(compass, std::move(dev), rotation);
77  if (!sensor || !sensor->init()) {
78  delete sensor;
79  return nullptr;
80  }
81 
82  return sensor;
83 }
84 
86 {
87  AP_HAL::Semaphore *bus_sem = _dev->get_semaphore();
88 
89  if (!bus_sem || !bus_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
90  hal.console->printf("LSM9DS1: Unable to get bus semaphore\n");
91  return false;
92  }
93 
94  if (!_check_id()) {
95  hal.console->printf("LSM9DS1: Could not check id\n");
96  goto errout;
97  }
98 
99  if (!_configure()) {
100  hal.console->printf("LSM9DS1: Could not check id\n");
101  goto errout;
102  }
103 
104  if (!_set_scale()) {
105  hal.console->printf("LSM9DS1: Could not set scale\n");
106  goto errout;
107  }
108 
110 
112 
115 
117 
118  bus_sem->give();
119 
120  return true;
121 
122 errout:
123  bus_sem->give();
124  return false;
125 }
126 
128 {
129  hal.console->printf("LSMDS1 registers\n");
130  for (uint8_t reg = LSM9DS1M_OFFSET_X_REG_L_M; reg <= LSM9DS1M_INT_THS_H_M; reg++) {
131  uint8_t v = _register_read(reg);
132  hal.console->printf("%02x:%02x ", (unsigned)reg, (unsigned)v);
133  if ((reg - (LSM9DS1M_OFFSET_X_REG_L_M-1)) % 16 == 0) {
134  hal.console->printf("\n");
135  }
136  }
137  hal.console->printf("\n");
138 }
139 
141 {
142  struct sample_regs regs;
143  Vector3f raw_field;
144 
145  if (!_block_read(LSM9DS1M_STATUS_REG_M, (uint8_t *) &regs, sizeof(regs))) {
146  return;
147  }
148 
149  if (regs.status & 0x80) {
150  return;
151  }
152 
153  raw_field = Vector3f(regs.val[0], regs.val[1], regs.val[2]);
154 
155  if (is_zero(raw_field.x) && is_zero(raw_field.y) && is_zero(raw_field.z)) {
156  return;
157  }
158 
159  raw_field *= _scaling;
160 
161  // rotate raw_field from sensor frame to body frame
162  rotate_field(raw_field, _compass_instance);
163 
164  // publish raw_field (uncorrected point sample) for calibration use
166 
167  // correct raw_field for known errors
168  correct_field(raw_field, _compass_instance);
169 
171  _mag_x_accum += raw_field.x;
172  _mag_y_accum += raw_field.y;
173  _mag_z_accum += raw_field.z;
174  _accum_count++;
175  if (_accum_count == 10) {
176  _mag_x_accum /= 2;
177  _mag_y_accum /= 2;
178  _mag_z_accum /= 2;
179  _accum_count = 5;
180  }
181  _sem->give();
182  }
183 }
184 
186 {
187  if (!_sem->take_nonblocking()) {
188  return;
189  }
190  if (_accum_count == 0) {
191  /* We're not ready to publish*/
192  _sem->give();
193  return;
194  }
195 
197  field /= _accum_count;
199  _accum_count = 0;
200 
201  _sem->give();
202 
204 }
205 
207 {
208  // initially run the bus at low speed
210 
212  if (value != WHO_AM_I_MAG) {
213  hal.console->printf("LSM9DS1: unexpected WHOAMI 0x%x\n", (unsigned)value);
214  return false;
215  }
216 
218 
219  return true;
220 }
221 
223 {
229 
230  return true;
231 }
232 
234 {
235  static const uint8_t FS_M_MASK = 0xc;
237  _scaling = 0.58f;
238 
239  return true;
240 }
241 
243 {
244  uint8_t val = 0;
245 
246  /* set READ bit */
247  reg |= 0x80;
248  _dev->read_registers(reg, &val, 1);
249 
250  return val;
251 }
252 
253 bool AP_Compass_LSM9DS1::_block_read(uint8_t reg, uint8_t *buf, uint32_t size)
254 {
255  /* set !MS bit */
256  reg |= 0xc0;
257  return _dev->read_registers(reg, buf, size);
258 }
259 
260 void AP_Compass_LSM9DS1::_register_write(uint8_t reg, uint8_t val)
261 {
262  _dev->write_register(reg, val);
263 }
264 
265 void AP_Compass_LSM9DS1::_register_modify(uint8_t reg, uint8_t clearbits, uint8_t setbits)
266 {
267  uint8_t val;
268 
269  val = _register_read(reg);
270  val &= ~clearbits;
271  val |= setbits;
272  _register_write(reg, val);
273 }
#define LSM9DS1M_TEMP_COMP
#define LSM9DS1M_XY_ULTRA_HIGH
Vector3< float > Vector3f
Definition: vector3.h:246
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
#define LSM9DS1M_STATUS_REG_M
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define LSM9DS1M_FAST_ODR
AP_HAL::UARTDriver * console
Definition: HAL.h:110
uint32_t get_bus_id(void) const
Definition: Device.h:60
bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size)
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
void _register_write(uint8_t reg, uint8_t val)
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
uint8_t _register_read(uint8_t reg)
#define LSM9DS1M_WHO_AM_I
void set_dev_id(uint8_t instance, uint32_t dev_id)
Rotation
Definition: rotations.h:27
#define LSM9DS1M_OFFSET_X_REG_L_M
void set_device_type(uint8_t devtype)
Definition: Device.h:70
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
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
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
AP_Compass_LSM9DS1(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation rotation=ROTATION_NONE)
void _register_modify(uint8_t reg, uint8_t clearbits, uint8_t setbits)
#define LSM9DS1M_INT_THS_H_M
#define LSM9DS1M_CTRL_REG3_M
#define WHO_AM_I_MAG
#define LSM9DS1M_FS_16G
virtual bool give()=0
float v
Definition: Printf.cpp:15
static Compass compass
Definition: AHRS_Test.cpp:20
AP_HAL::Semaphore * _sem
#define LSM9DS1M_CTRL_REG5_M
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation rotation=ROTATION_NONE)
enum Rotation _rotation
#define LSM9DS1M_CTRL_REG4_M
#define LSM9DS1M_BDU
void set_rotation(uint8_t instance, enum Rotation rotation)
AP_HAL::OwnPtr< AP_HAL::Device > _dev
#define PACKED
Definition: AP_Common.h:28
#define LSM9DS1M_80HZ
float value
#define LSM9DS1M_CTRL_REG1_M
#define LSM9DS1M_CONTINUOUS_MODE
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 LSM9DS1M_CTRL_REG2_M
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
#define LSM9DS1M_Z_ULTRA_HIGH