PX4 Firmware
PX4 Autopilot Software http://px4.io
LSM303D.hpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2013-2019 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file LSM303D.hpp
36  * Driver for the ST LSM303D MEMS accelerometer / magnetometer connected via SPI.
37  */
38 
39 #pragma once
40 
41 #include <drivers/device/spi.h>
42 #include <ecl/geo/geo.h>
43 #include <perf/perf_counter.h>
44 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
47 
48 /* SPI protocol address bits */
49 #define DIR_READ (1<<7)
50 #define DIR_WRITE (0<<7)
51 #define ADDR_INCREMENT (1<<6)
52 
53 /* register addresses: A: accel, M: mag, T: temp */
54 #define ADDR_WHO_AM_I 0x0F
55 #define WHO_I_AM 0x49
56 
57 #define ADDR_OUT_TEMP_L 0x05
58 
59 #define ADDR_STATUS_A 0x27
60 
61 #define ADDR_CTRL_REG0 0x1F
62 #define ADDR_CTRL_REG1 0x20
63 #define ADDR_CTRL_REG2 0x21
64 #define ADDR_CTRL_REG3 0x22
65 #define ADDR_CTRL_REG4 0x23
66 #define ADDR_CTRL_REG5 0x24
67 #define ADDR_CTRL_REG6 0x25
68 #define ADDR_CTRL_REG7 0x26
69 
70 #define REG1_RATE_BITS_A ((1<<7) | (1<<6) | (1<<5) | (1<<4))
71 #define REG1_POWERDOWN_A ((0<<7) | (0<<6) | (0<<5) | (0<<4))
72 #define REG1_RATE_3_125HZ_A ((0<<7) | (0<<6) | (0<<5) | (1<<4))
73 #define REG1_RATE_6_25HZ_A ((0<<7) | (0<<6) | (1<<5) | (0<<4))
74 #define REG1_RATE_12_5HZ_A ((0<<7) | (0<<6) | (1<<5) | (1<<4))
75 #define REG1_RATE_25HZ_A ((0<<7) | (1<<6) | (0<<5) | (0<<4))
76 #define REG1_RATE_50HZ_A ((0<<7) | (1<<6) | (0<<5) | (1<<4))
77 #define REG1_RATE_100HZ_A ((0<<7) | (1<<6) | (1<<5) | (0<<4))
78 #define REG1_RATE_200HZ_A ((0<<7) | (1<<6) | (1<<5) | (1<<4))
79 #define REG1_RATE_400HZ_A ((1<<7) | (0<<6) | (0<<5) | (0<<4))
80 #define REG1_RATE_800HZ_A ((1<<7) | (0<<6) | (0<<5) | (1<<4))
81 #define REG1_RATE_1600HZ_A ((1<<7) | (0<<6) | (1<<5) | (0<<4))
82 
83 #define REG1_BDU_UPDATE (1<<3)
84 #define REG1_Z_ENABLE_A (1<<2)
85 #define REG1_Y_ENABLE_A (1<<1)
86 #define REG1_X_ENABLE_A (1<<0)
87 
88 #define REG2_ANTIALIAS_FILTER_BW_BITS_A ((1<<7) | (1<<6))
89 #define REG2_AA_FILTER_BW_773HZ_A ((0<<7) | (0<<6))
90 #define REG2_AA_FILTER_BW_194HZ_A ((0<<7) | (1<<6))
91 #define REG2_AA_FILTER_BW_362HZ_A ((1<<7) | (0<<6))
92 #define REG2_AA_FILTER_BW_50HZ_A ((1<<7) | (1<<6))
93 
94 #define REG2_FULL_SCALE_BITS_A ((1<<5) | (1<<4) | (1<<3))
95 #define REG2_FULL_SCALE_2G_A ((0<<5) | (0<<4) | (0<<3))
96 #define REG2_FULL_SCALE_4G_A ((0<<5) | (0<<4) | (1<<3))
97 #define REG2_FULL_SCALE_6G_A ((0<<5) | (1<<4) | (0<<3))
98 #define REG2_FULL_SCALE_8G_A ((0<<5) | (1<<4) | (1<<3))
99 #define REG2_FULL_SCALE_16G_A ((1<<5) | (0<<4) | (0<<3))
100 
101 #define REG5_ENABLE_T (1<<7)
102 
103 #define REG5_RES_HIGH_M ((1<<6) | (1<<5))
104 #define REG5_RES_LOW_M ((0<<6) | (0<<5))
105 
106 #define REG5_RATE_BITS_M ((1<<4) | (1<<3) | (1<<2))
107 #define REG5_RATE_3_125HZ_M ((0<<4) | (0<<3) | (0<<2))
108 #define REG5_RATE_6_25HZ_M ((0<<4) | (0<<3) | (1<<2))
109 #define REG5_RATE_12_5HZ_M ((0<<4) | (1<<3) | (0<<2))
110 #define REG5_RATE_25HZ_M ((0<<4) | (1<<3) | (1<<2))
111 #define REG5_RATE_50HZ_M ((1<<4) | (0<<3) | (0<<2))
112 #define REG5_RATE_100HZ_M ((1<<4) | (0<<3) | (1<<2))
113 #define REG5_RATE_DO_NOT_USE_M ((1<<4) | (1<<3) | (0<<2))
114 
115 #define REG6_FULL_SCALE_BITS_M ((1<<6) | (1<<5))
116 #define REG6_FULL_SCALE_2GA_M ((0<<6) | (0<<5))
117 #define REG6_FULL_SCALE_4GA_M ((0<<6) | (1<<5))
118 #define REG6_FULL_SCALE_8GA_M ((1<<6) | (0<<5))
119 #define REG6_FULL_SCALE_12GA_M ((1<<6) | (1<<5))
120 
121 #define REG7_CONT_MODE_M ((0<<1) | (0<<0))
122 
123 #define REG_STATUS_A_NEW_ZYXADA 0x08
124 
125 /* default values for this device */
126 #define LSM303D_ACCEL_DEFAULT_RANGE_G 16
127 #define LSM303D_ACCEL_DEFAULT_RATE 800
128 #define LSM303D_ACCEL_DEFAULT_ONCHIP_FILTER_FREQ 50
129 
130 #define LSM303D_MAG_DEFAULT_RANGE_GA 2
131 #define LSM303D_MAG_DEFAULT_RATE 100
132 
133 /*
134  we set the timer interrupt to run a bit faster than the desired
135  sample rate and then throw away duplicates using the data ready bit.
136  This time reduction is enough to cope with worst case timing jitter
137  due to other timers
138  */
139 #define LSM303D_TIMER_REDUCTION 200
140 
141 extern "C" { __EXPORT int lsm303d_main(int argc, char *argv[]); }
142 
143 class LSM303D : public device::SPI, public px4::ScheduledWorkItem
144 {
145 public:
146  LSM303D(int bus, uint32_t device, enum Rotation rotation);
147  virtual ~LSM303D();
148 
149  int init() override;
150 
151  /**
152  * Diagnostics - print some basic information about the driver.
153  */
154  void print_info();
155 
156 protected:
157  virtual int probe();
158 
159 private:
160 
161  void Run() override;
162 
163  void start();
164  void stop();
165  void reset();
166 
167  /**
168  * disable I2C on the chip
169  */
170  void disable_i2c();
171 
172  /**
173  * check key registers for correct values
174  */
175  void check_registers(void);
176 
177  /**
178  * Fetch accel measurements from the sensor and update the report ring.
179  */
180  void measureAccelerometer();
181 
182  /**
183  * Fetch mag measurements from the sensor and update the report ring.
184  */
185  void measureMagnetometer();
186 
187  /**
188  * Read a register from the LSM303D
189  *
190  * @param The register to read.
191  * @return The value that was read.
192  */
193  uint8_t read_reg(unsigned reg);
194 
195  /**
196  * Write a register in the LSM303D
197  *
198  * @param reg The register to write.
199  * @param value The new value to write.
200  */
201  void write_reg(unsigned reg, uint8_t value);
202 
203  /**
204  * Modify a register in the LSM303D
205  *
206  * Bits are cleared before bits are set.
207  *
208  * @param reg The register to modify.
209  * @param clearbits Bits in the register to clear.
210  * @param setbits Bits in the register to set.
211  */
212  void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
213 
214  /**
215  * Write a register in the LSM303D, updating _checked_values
216  *
217  * @param reg The register to write.
218  * @param value The new value to write.
219  */
220  void write_checked_reg(unsigned reg, uint8_t value);
221 
222  /**
223  * Set the LSM303D accel measurement range.
224  *
225  * @param max_g The measurement range of the accel is in g (9.81m/s^2)
226  * Zero selects the maximum supported range.
227  * @return OK if the value can be supported, -ERANGE otherwise.
228  */
229  int accel_set_range(unsigned max_g);
230 
231  /**
232  * Set the LSM303D mag measurement range.
233  *
234  * @param max_ga The measurement range of the mag is in Ga
235  * Zero selects the maximum supported range.
236  * @return OK if the value can be supported, -ERANGE otherwise.
237  */
238  int mag_set_range(unsigned max_g);
239 
240  /**
241  * Set the LSM303D on-chip anti-alias filter bandwith.
242  *
243  * @param bandwidth The anti-alias filter bandwidth in Hz
244  * Zero selects the highest bandwidth
245  * @return OK if the value can be supported, -ERANGE otherwise.
246  */
247  int accel_set_onchip_lowpass_filter_bandwidth(unsigned bandwidth);
248 
249  /**
250  * Set the LSM303D internal accel sampling frequency.
251  *
252  * @param frequency The internal accel sampling frequency is set to not less than
253  * this value.
254  * Zero selects the maximum rate supported.
255  * @return OK if the value can be supported.
256  */
257  int accel_set_samplerate(unsigned frequency);
258 
259  /**
260  * Set the LSM303D internal mag sampling frequency.
261  *
262  * @param frequency The internal mag sampling frequency is set to not less than
263  * this value.
264  * Zero selects the maximum rate supported.
265  * @return OK if the value can be supported.
266  */
267  int mag_set_samplerate(unsigned frequency);
268 
269 
272 
275 
281 
282  uint8_t _register_wait{0};
283 
284  int16_t _last_accel[3] {};
286 
288 
289  float _last_temperature{0.0f};
290 
291  // this is used to support runtime checking of key
292  // configuration registers to detect SPI bus errors and sensor
293  // reset
294  static constexpr int LSM303D_NUM_CHECKED_REGISTERS{8};
296  uint8_t _checked_next{0};
297 
298 };
void check_registers(void)
check key registers for correct values
Definition: LSM303D.cpp:436
uint8_t _checked_values[LSM303D_NUM_CHECKED_REGISTERS]
Definition: LSM303D.hpp:295
int mag_set_samplerate(unsigned frequency)
Set the LSM303D internal mag sampling frequency.
Definition: LSM303D.cpp:374
perf_counter_t _bad_registers
Definition: LSM303D.hpp:278
uint8_t _constant_accel_count
Definition: LSM303D.hpp:285
void write_checked_reg(unsigned reg, uint8_t value)
Write a register in the LSM303D, updating _checked_values.
Definition: LSM303D.cpp:183
Definition of geo / math functions to perform geodesic calculations.
PX4Accelerometer _px4_accel
Definition: LSM303D.hpp:270
void reset()
Definition: LSM303D.cpp:117
void Run() override
Definition: LSM303D.cpp:425
virtual int probe()
Definition: LSM303D.cpp:146
Definition: I2C.hpp:51
void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits)
Modify a register in the LSM303D.
Definition: LSM303D.cpp:195
uint8_t read_reg(unsigned reg)
Read a register from the LSM303D.
Definition: LSM303D.cpp:161
int init() override
Definition: LSM303D.cpp:86
PX4Magnetometer _px4_mag
Definition: LSM303D.hpp:271
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
int accel_set_onchip_lowpass_filter_bandwidth(unsigned bandwidth)
Set the LSM303D on-chip anti-alias filter bandwith.
Definition: LSM303D.cpp:295
uint8_t _register_wait
Definition: LSM303D.hpp:282
float _last_temperature
Definition: LSM303D.hpp:289
int accel_set_samplerate(unsigned frequency)
Set the LSM303D internal accel sampling frequency.
Definition: LSM303D.cpp:330
void print_info()
Diagnostics - print some basic information about the driver.
Definition: LSM303D.cpp:585
perf_counter_t _accel_sample_perf
Definition: LSM303D.hpp:276
perf_counter_t _bad_values
Definition: LSM303D.hpp:279
Header common to all counters.
#define LSM303D_ACCEL_DEFAULT_RATE
Definition: LSM303D.hpp:127
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
unsigned _call_accel_interval
Definition: LSM303D.hpp:273
void write_reg(unsigned reg, uint8_t value)
Write a register in the LSM303D.
Definition: LSM303D.cpp:172
unsigned _call_mag_interval
Definition: LSM303D.hpp:274
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
perf_counter_t _accel_duplicates
Definition: LSM303D.hpp:280
LSM303D(int bus, uint32_t device, enum Rotation rotation)
Definition: LSM303D.cpp:56
#define LSM303D_MAG_DEFAULT_RATE
Definition: LSM303D.hpp:131
perf_counter_t _mag_sample_perf
Definition: LSM303D.hpp:277
virtual ~LSM303D()
Definition: LSM303D.cpp:72
void measureAccelerometer()
Fetch accel measurements from the sensor and update the report ring.
Definition: LSM303D.cpp:466
int accel_set_range(unsigned max_g)
Set the LSM303D accel measurement range.
Definition: LSM303D.cpp:204
uint8_t _checked_next
Definition: LSM303D.hpp:296
hrt_abstime _mag_last_measure
Definition: LSM303D.hpp:287
__EXPORT int lsm303d_main(int argc, char *argv[])
void stop()
Definition: LSM303D.cpp:419
static constexpr int LSM303D_NUM_CHECKED_REGISTERS
Definition: LSM303D.hpp:294
int mag_set_range(unsigned max_g)
Set the LSM303D mag measurement range.
Definition: LSM303D.cpp:253
void disable_i2c()
disable I2C on the chip
Definition: LSM303D.cpp:104
void measureMagnetometer()
Fetch mag measurements from the sensor and update the report ring.
Definition: LSM303D.cpp:547
Performance measuring tools.
void start()
Definition: LSM303D.cpp:409
int16_t _last_accel[3]
Definition: LSM303D.hpp:284