APM:Libraries
AP_InertialSensor_LSM9DS0.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 
16 #include <AP_HAL/AP_HAL.h>
17 
19 
20 #include <utility>
21 
22 extern const AP_HAL::HAL &hal;
23 
24 #define LSM9DS0_DRY_X_PIN -1
25 #define LSM9DS0_DRY_G_PIN -1
26 
27 #define LSM9DS0_G_WHOAMI 0xD4 // L3GD20
28 #define LSM9DS0_G_WHOAMI_H 0xD7 // L3GD20H
29 #define LSM9DS0_XM_WHOAMI 0x49
30 
32 // LSM9DS0 Gyro Registers //
34 #define WHO_AM_I_G 0x0F
35 #define CTRL_REG1_G 0x20
36 # define CTRL_REG1_G_DR_95Hz_BW_12500mHz (0x0 << 4)
37 # define CTRL_REG1_G_DR_95Hz_BW_25Hz (0x1 << 4)
38 # define CTRL_REG1_G_DR_190Hz_BW_12500mHz (0x4 << 4)
39 # define CTRL_REG1_G_DR_190Hz_BW_25Hz (0x5 << 4)
40 # define CTRL_REG1_G_DR_190Hz_BW_50Hz (0x6 << 4)
41 # define CTRL_REG1_G_DR_190Hz_BW_70Hz (0x7 << 4)
42 # define CTRL_REG1_G_DR_380Hz_BW_20Hz (0x8 << 4)
43 # define CTRL_REG1_G_DR_380Hz_BW_25Hz (0x9 << 4)
44 # define CTRL_REG1_G_DR_380Hz_BW_50Hz (0xA << 4)
45 # define CTRL_REG1_G_DR_380Hz_BW_100Hz (0xB << 4)
46 # define CTRL_REG1_G_DR_760Hz_BW_30Hz (0xC << 4)
47 # define CTRL_REG1_G_DR_760Hz_BW_35Hz (0xD << 4)
48 # define CTRL_REG1_G_DR_760Hz_BW_50Hz (0xE << 4)
49 # define CTRL_REG1_G_DR_760Hz_BW_100Hz (0xF << 4)
50 # define CTRL_REG1_G_PD (0x1 << 3)
51 # define CTRL_REG1_G_ZEN (0x1 << 2)
52 # define CTRL_REG1_G_YEN (0x1 << 1)
53 # define CTRL_REG1_G_XEN (0x1 << 0)
54 #define CTRL_REG2_G 0x21
55 # define CTRL_REG2_G_HPM_NORMAL_RESET (0x0 << 4)
56 # define CTRL_REG2_G_HPM_REFERENCE (0x1 << 4)
57 # define CTRL_REG2_G_HPM_NORMAL (0x2 << 4)
58 # define CTRL_REG2_G_HPM_AUTORESET (0x3 << 4)
59 # define CTRL_REG2_G_HPCF_0 (0x0 << 0)
60 # define CTRL_REG2_G_HPCF_1 (0x1 << 0)
61 # define CTRL_REG2_G_HPCF_2 (0x2 << 0)
62 # define CTRL_REG2_G_HPCF_3 (0x3 << 0)
63 # define CTRL_REG2_G_HPCF_4 (0x4 << 0)
64 # define CTRL_REG2_G_HPCF_5 (0x5 << 0)
65 # define CTRL_REG2_G_HPCF_6 (0x6 << 0)
66 # define CTRL_REG2_G_HPCF_7 (0x7 << 0)
67 # define CTRL_REG2_G_HPCF_8 (0x8 << 0)
68 # define CTRL_REG2_G_HPCF_9 (0x9 << 0)
69 #define CTRL_REG3_G 0x22
70 # define CTRL_REG3_G_I1_INT1 (0x1 << 7)
71 # define CTRL_REG3_G_I1_BOOT (0x1 << 6)
72 # define CTRL_REG3_G_H_LACTIVE (0x1 << 5)
73 # define CTRL_REG3_G_PP_OD (0x1 << 4)
74 # define CTRL_REG3_G_I2_DRDY (0x1 << 3)
75 # define CTRL_REG3_G_I2_WTM (0x1 << 2)
76 # define CTRL_REG3_G_I2_ORUN (0x1 << 1)
77 # define CTRL_REG3_G_I2_EMPTY (0x1 << 0)
78 #define CTRL_REG4_G 0x23
79 # define CTRL_REG4_G_BDU (0x1 << 7)
80 # define CTRL_REG4_G_BLE (0x1 << 6)
81 # define CTRL_REG4_G_FS_245DPS (0x0 << 4)
82 # define CTRL_REG4_G_FS_500DPS (0x1 << 4)
83 # define CTRL_REG4_G_FS_2000DPS (0x2 << 4)
84 # define CTRL_REG4_G_ST_NORMAL (0x0 << 1)
85 # define CTRL_REG4_G_ST_0 (0x1 << 1)
86 # define CTRL_REG4_G_ST_1 (0x3 << 1)
87 # define CTRL_REG4_G_SIM_3WIRE (0x1 << 0)
88 #define CTRL_REG5_G 0x24
89 # define CTRL_REG5_G_BOOT (0x1 << 7)
90 # define CTRL_REG5_G_FIFO_EN (0x1 << 6)
91 # define CTRL_REG5_G_HPEN (0x1 << 4)
92 # define CTRL_REG5_G_INT1_SEL_00 (0x0 << 2)
93 # define CTRL_REG5_G_INT1_SEL_01 (0x1 << 2)
94 # define CTRL_REG5_G_INT1_SEL_10 (0x2 << 2)
95 # define CTRL_REG5_G_INT1_SEL_11 (0x3 << 2)
96 # define CTRL_REG5_G_OUT_SEL_00 (0x0 << 0)
97 # define CTRL_REG5_G_OUT_SEL_01 (0x1 << 0)
98 # define CTRL_REG5_G_OUT_SEL_10 (0x2 << 0)
99 # define CTRL_REG5_G_OUT_SEL_11 (0x3 << 0)
100 #define REFERENCE_G 0x25
101 #define STATUS_REG_G 0x27
102 # define STATUS_REG_G_ZYXOR (0x1 << 7)
103 # define STATUS_REG_G_ZOR (0x1 << 6)
104 # define STATUS_REG_G_YOR (0x1 << 5)
105 # define STATUS_REG_G_XOR (0x1 << 4)
106 # define STATUS_REG_G_ZYXDA (0x1 << 3)
107 # define STATUS_REG_G_ZDA (0x1 << 2)
108 # define STATUS_REG_G_YDA (0x1 << 1)
109 # define STATUS_REG_G_XDA (0x1 << 0)
110 #define OUT_X_L_G 0x28
111 #define OUT_X_H_G 0x29
112 #define OUT_Y_L_G 0x2A
113 #define OUT_Y_H_G 0x2B
114 #define OUT_Z_L_G 0x2C
115 #define OUT_Z_H_G 0x2D
116 #define FIFO_CTRL_REG_G 0x2E
117 # define FIFO_CTRL_REG_G_FM_BYPASS (0x0 << 5)
118 # define FIFO_CTRL_REG_G_FM_FIFO (0x1 << 5)
119 # define FIFO_CTRL_REG_G_FM_STREAM (0x2 << 5)
120 # define FIFO_CTRL_REG_G_FM_STREAM_TO_FIFO (0x3 << 5)
121 # define FIFO_CTRL_REG_G_FM_BYPASS_TO_STREAM (0x4 << 5)
122 # define FIFO_CTRL_REG_G_WTM_MASK 0x1F
123 #define FIFO_SRC_REG_G 0x2F
124 # define FIFO_SRC_REG_G_WTM (0x1 << 7)
125 # define FIFO_SRC_REG_G_OVRN (0x1 << 6)
126 # define FIFO_SRC_REG_G_EMPTY (0x1 << 5)
127 # define FIFO_SRC_REG_G_FSS_MASK 0x1F
128 #define INT1_CFG_G 0x30
129 # define INT1_CFG_G_AND_OR (0x1 << 7)
130 # define INT1_CFG_G_LIR (0x1 << 6)
131 # define INT1_CFG_G_ZHIE (0x1 << 5)
132 # define INT1_CFG_G_ZLIE (0x1 << 4)
133 # define INT1_CFG_G_YHIE (0x1 << 3)
134 # define INT1_CFG_G_YLIE (0x1 << 2)
135 # define INT1_CFG_G_XHIE (0x1 << 1)
136 # define INT1_CFG_G_XLIE (0x1 << 0)
137 #define INT1_SRC_G 0x31
138 # define INT1_SRC_G_IA (0x1 << 6)
139 # define INT1_SRC_G_ZH (0x1 << 5)
140 # define INT1_SRC_G_ZL (0x1 << 4)
141 # define INT1_SRC_G_YH (0x1 << 3)
142 # define INT1_SRC_G_YL (0x1 << 2)
143 # define INT1_SRC_G_XH (0x1 << 1)
144 # define INT1_SRC_G_XL (0x1 << 0)
145 #define INT1_THS_XH_G 0x32
146 #define INT1_THS_XL_G 0x33
147 #define INT1_THS_YH_G 0x34
148 #define INT1_THS_YL_G 0x35
149 #define INT1_THS_ZH_G 0x36
150 #define INT1_THS_ZL_G 0x37
151 #define INT1_DURATION_G 0x38
152 # define INT1_DURATION_G_WAIT (0x1 << 7)
153 # define INT1_DURATION_G_D_MASK 0x7F
154 
156 // LSM9DS0 Accel/Magneto (XM) Registers //
158 #define OUT_TEMP_L_XM 0x05
159 #define OUT_TEMP_H_XM 0x06
160 #define STATUS_REG_M 0x07
161 # define STATUS_REG_M_ZYXMOR (0x1 << 7)
162 # define STATUS_REG_M_ZMOR (0x1 << 6)
163 # define STATUS_REG_M_YMOR (0x1 << 5)
164 # define STATUS_REG_M_XMOR (0x1 << 4)
165 # define STATUS_REG_M_ZYXMDA (0x1 << 3)
166 # define STATUS_REG_M_ZMDA (0x1 << 2)
167 # define STATUS_REG_M_YMDA (0x1 << 1)
168 # define STATUS_REG_M_XMDA (0x1 << 0)
169 #define OUT_X_L_M 0x08
170 #define OUT_X_H_M 0x09
171 #define OUT_Y_L_M 0x0A
172 #define OUT_Y_H_M 0x0B
173 #define OUT_Z_L_M 0x0C
174 #define OUT_Z_H_M 0x0D
175 #define WHO_AM_I_XM 0x0F
176 #define INT_CTRL_REG_M 0x12
177 # define INT_CTRL_REG_M_XMIEN (0x1 << 7)
178 # define INT_CTRL_REG_M_YMIEN (0x1 << 6)
179 # define INT_CTRL_REG_M_ZMIEN (0x1 << 5)
180 # define INT_CTRL_REG_M_PP_OD (0x1 << 4)
181 # define INT_CTRL_REG_M_IEA (0x1 << 3)
182 # define INT_CTRL_REG_M_IEL (0x1 << 2)
183 # define INT_CTRL_REG_M_4D (0x1 << 1)
184 # define INT_CTRL_REG_M_MIEN (0x1 << 0)
185 #define INT_SRC_REG_M 0x13
186 # define INT_SRC_REG_M_M_PTH_X (0x1 << 7)
187 # define INT_SRC_REG_M_M_PTH_Y (0x1 << 6)
188 # define INT_SRC_REG_M_M_PTH_Z (0x1 << 5)
189 # define INT_SRC_REG_M_M_NTH_X (0x1 << 4)
190 # define INT_SRC_REG_M_M_NTH_Y (0x1 << 3)
191 # define INT_SRC_REG_M_M_NTH_Z (0x1 << 2)
192 # define INT_SRC_REG_M_MROI (0x1 << 1)
193 # define INT_SRC_REG_M_MINT (0x1 << 0)
194 #define INT_THS_L_M 0x14
195 #define INT_THS_H_M 0x15
196 #define OFFSET_X_L_M 0x16
197 #define OFFSET_X_H_M 0x17
198 #define OFFSET_Y_L_M 0x18
199 #define OFFSET_Y_H_M 0x19
200 #define OFFSET_Z_L_M 0x1A
201 #define OFFSET_Z_H_M 0x1B
202 #define REFERENCE_X 0x1C
203 #define REFERENCE_Y 0x1D
204 #define REFERENCE_Z 0x1E
205 #define CTRL_REG0_XM 0x1F
206 # define CTRL_REG0_XM_B00T (0x1 << 7)
207 # define CTRL_REG0_XM_FIFO_EN (0x1 << 6)
208 # define CTRL_REG0_XM_WTM_EN (0x1 << 5)
209 # define CTRL_REG0_XM_HP_CLICK (0x1 << 2)
210 # define CTRL_REG0_XM_HPIS1 (0x1 << 1)
211 # define CTRL_REG0_XM_HPIS2 (0x1 << 0)
212 #define CTRL_REG1_XM 0x20
213 # define CTRL_REG1_XM_AODR_POWERDOWN (0x0 << 4)
214 # define CTRL_REG1_XM_AODR_3125mHz (0x1 << 4)
215 # define CTRL_REG1_XM_AODR_6250mHz (0x2 << 4)
216 # define CTRL_REG1_XM_AODR_12500mHz (0x3 << 4)
217 # define CTRL_REG1_XM_AODR_25Hz (0x4 << 4)
218 # define CTRL_REG1_XM_AODR_50Hz (0x5 << 4)
219 # define CTRL_REG1_XM_AODR_100Hz (0x6 << 4)
220 # define CTRL_REG1_XM_AODR_200Hz (0x7 << 4)
221 # define CTRL_REG1_XM_AODR_400Hz (0x8 << 4)
222 # define CTRL_REG1_XM_AODR_800Hz (0x9 << 4)
223 # define CTRL_REG1_XM_AODR_1600Hz (0xA << 4)
224 # define CTRL_REG1_XM_BDU (0x1 << 3)
225 # define CTRL_REG1_XM_AZEN (0x1 << 2)
226 # define CTRL_REG1_XM_AYEN (0x1 << 1)
227 # define CTRL_REG1_XM_AXEN (0x1 << 0)
228 #define CTRL_REG2_XM 0x21
229 # define CTRL_REG2_XM_ABW_773Hz (0x0 << 6)
230 # define CTRL_REG2_XM_ABW_194Hz (0x1 << 6)
231 # define CTRL_REG2_XM_ABW_362Hz (0x2 << 6)
232 # define CTRL_REG2_XM_ABW_50Hz (0x3 << 6)
233 # define CTRL_REG2_XM_AFS_2G (0x0 << 3)
234 # define CTRL_REG2_XM_AFS_4G (0x1 << 3)
235 # define CTRL_REG2_XM_AFS_6G (0x2 << 3)
236 # define CTRL_REG2_XM_AFS_8G (0x3 << 3)
237 # define CTRL_REG2_XM_AFS_16G (0x4 << 3)
238 # define CTRL_REG2_XM_AST_NORMAL (0x0 << 1)
239 # define CTRL_REG2_XM_AST_POSITIVE (0x1 << 1)
240 # define CTRL_REG2_XM_AST_NEGATIVE (0x2 << 1)
241 # define CTRL_REG2_XM_SIM_3WIRE (0x1 << 0)
242 #define CTRL_REG3_XM 0x22
243 # define CTRL_REG3_XM_P1_BOOT (0x1 << 7)
244 # define CTRL_REG3_XM_P1_TAP (0x1 << 6)
245 # define CTRL_REG3_XM_P1_INT1 (0x1 << 5)
246 # define CTRL_REG3_XM_P1_INT2 (0x1 << 4)
247 # define CTRL_REG3_XM_P1_INTM (0x1 << 3)
248 # define CTRL_REG3_XM_P1_DRDYA (0x1 << 2)
249 # define CTRL_REG3_XM_P1_DRDYM (0x1 << 1)
250 # define CTRL_REG3_XM_P1_EMPTY (0x1 << 0)
251 #define CTRL_REG4_XM 0x23
252 # define CTRL_REG4_XM_P2_TAP (0x1 << 7)
253 # define CTRL_REG4_XM_P2_INT1 (0x1 << 6)
254 # define CTRL_REG4_XM_P2_INT2 (0x1 << 5)
255 # define CTRL_REG4_XM_P2_INTM (0x1 << 4)
256 # define CTRL_REG4_XM_P2_DRDYA (0x1 << 3)
257 # define CTRL_REG4_XM_P2_DRDYM (0x1 << 2)
258 # define CTRL_REG4_XM_P2_OVERRUN (0x1 << 1)
259 # define CTRL_REG4_XM_P2_WTM (0x1 << 0)
260 #define CTRL_REG5_XM 0x24
261 # define CTRL_REG5_XM_TEMP_EN (0x1 << 7)
262 # define CTRL_REG5_XM_M_RES_LOW (0x0 << 5)
263 # define CTRL_REG5_XM_M_RES_HIGH (0x3 << 5)
264 # define CTRL_REG5_XM_ODR_3125mHz (0x0 << 2)
265 # define CTRL_REG5_XM_ODR_6250mHz (0x1 << 2)
266 # define CTRL_REG5_XM_ODR_12500mHz (0x2 << 2)
267 # define CTRL_REG5_XM_ODR_25Hz (0x3 << 2)
268 # define CTRL_REG5_XM_ODR_50Hz (0x4 << 2)
269 # define CTRL_REG5_XM_ODR_100Hz (0x5 << 2)
270 # define CTRL_REG5_XM_LIR2 (0x1 << 1)
271 # define CTRL_REG5_XM_LIR1 (0x1 << 0)
272 #define CTRL_REG6_XM 0x25
273 # define CTRL_REG6_XM_MFS_2Gs (0x0 << 5)
274 # define CTRL_REG6_XM_MFS_4Gs (0x1 << 5)
275 # define CTRL_REG6_XM_MFS_8Gs (0x2 << 5)
276 # define CTRL_REG6_XM_MFS_12Gs (0x3 << 5)
277 #define CTRL_REG7_XM 0x26
278 # define CTRL_REG7_XM_AHPM_NORMAL_RESET (0x0 << 6)
279 # define CTRL_REG7_XM_AHPM_REFERENCE (0x1 << 6)
280 # define CTRL_REG7_XM_AHPM_NORMAL (0x2 << 6)
281 # define CTRL_REG7_XM_AHPM_AUTORESET (0x3 << 6)
282 # define CTRL_REG7_XM_AFDS (0x1 << 5)
283 # define CTRL_REG7_XM_MLP (0x1 << 2)
284 # define CTRL_REG7_XM_MD_CONTINUOUS (0x0 << 0)
285 # define CTRL_REG7_XM_MD_SINGLE (0x1 << 0)
286 # define CTRL_REG7_XM_MD_POWERDOWN (0x2 << 0)
287 #define STATUS_REG_A 0x27
288 # define STATUS_REG_A_ZYXAOR (0x1 << 7)
289 # define STATUS_REG_A_ZAOR (0x1 << 6)
290 # define STATUS_REG_A_YAOR (0x1 << 5)
291 # define STATUS_REG_A_XAOR (0x1 << 4)
292 # define STATUS_REG_A_ZYXADA (0x1 << 3)
293 # define STATUS_REG_A_ZADA (0x1 << 2)
294 # define STATUS_REG_A_YADA (0x1 << 1)
295 # define STATUS_REG_A_XADA (0x1 << 0)
296 #define OUT_X_L_A 0x28
297 #define OUT_X_H_A 0x29
298 #define OUT_Y_L_A 0x2A
299 #define OUT_Y_H_A 0x2B
300 #define OUT_Z_L_A 0x2C
301 #define OUT_Z_H_A 0x2D
302 #define FIFO_CTRL_REG 0x2E
303 # define FIFO_CTRL_REG_FM_BYPASS (0x0 << 5)
304 # define FIFO_CTRL_REG_FM_FIFO (0x1 << 5)
305 # define FIFO_CTRL_REG_FM_STREAM (0x2 << 5)
306 # define FIFO_CTRL_REG_FM_STREAM_TO_FIFO (0x3 << 5)
307 # define FIFO_CTRL_REG_FM_BYPASS_TO_STREAM (0x4 << 5)
308 # define FIFO_CTRL_REG_FTH_MASK 0x1F
309 #define FIFO_SRC_REG 0x2F
310 # define FIFO_SRC_REG_WTM (0x1 << 7)
311 # define FIFO_SRC_REG_OVRN (0x1 << 6)
312 # define FIFO_SRC_REG_EMPTY (0x1 << 5)
313 # define FIFO_SRC_REG_FSS_MASK 0x1F
314 #define INT_GEN_1_REG 0x30
315 # define INT_GEN_1_REG_AOI (0x1 << 7)
316 # define INT_GEN_1_REG_6D (0x1 << 6)
317 # define INT_GEN_1_REG_ZHIE_ZUPE (0x1 << 5)
318 # define INT_GEN_1_REG_ZLIE_ZDOWNE (0x1 << 4)
319 # define INT_GEN_1_REG_YHIE_YUPE (0x1 << 3)
320 # define INT_GEN_1_REG_YLIE_YDOWNE (0x1 << 2)
321 # define INT_GEN_1_REG_XHIE_XUPE (0x1 << 1)
322 # define INT_GEN_1_REG_XLIE_XDOWNE (0x1 << 0)
323 #define INT_GEN_1_SRC 0x31
324 # define INT_GEN_1_SRC_IA (0x1 << 6)
325 # define INT_GEN_1_SRC_ZH (0x1 << 5)
326 # define INT_GEN_1_SRC_ZL (0x1 << 4)
327 # define INT_GEN_1_SRC_YH (0x1 << 3)
328 # define INT_GEN_1_SRC_YL (0x1 << 2)
329 # define INT_GEN_1_SRC_XH (0x1 << 1)
330 # define INT_GEN_1_SRC_XL (0x1 << 0)
331 #define INT_GEN_1_THS 0x32
332 #define INT_GEN_1_DURATION 0x33
333 #define INT_GEN_2_REG 0x34
334 # define INT_GEN_2_REG_AOI (0x1 << 7)
335 # define INT_GEN_2_REG_6D (0x1 << 6)
336 # define INT_GEN_2_REG_ZHIE_ZUPE (0x1 << 5)
337 # define INT_GEN_2_REG_ZLIE_ZDOWNE (0x1 << 4)
338 # define INT_GEN_2_REG_YHIE_YUPE (0x1 << 3)
339 # define INT_GEN_2_REG_YLIE_YDOWNE (0x1 << 2)
340 # define INT_GEN_2_REG_XHIE_XUPE (0x1 << 1)
341 # define INT_GEN_2_REG_XLIE_XDOWNE (0x1 << 0)
342 #define INT_GEN_2_SRC 0x35
343 # define INT_GEN_2_SRC_IA (0x1 << 6)
344 # define INT_GEN_2_SRC_ZH (0x1 << 5)
345 # define INT_GEN_2_SRC_ZL (0x1 << 4)
346 # define INT_GEN_2_SRC_YH (0x1 << 3)
347 # define INT_GEN_2_SRC_YL (0x1 << 2)
348 # define INT_GEN_2_SRC_XH (0x1 << 1)
349 # define INT_GEN_2_SRC_XL (0x1 << 0)
350 #define INT_GEN_2_THS 0x36
351 #define INT_GEN_2_DURATION 0x37
352 #define CLICK_CFG 0x38
353 # define CLICK_CFG_ZD (0x1 << 5)
354 # define CLICK_CFG_ZS (0x1 << 4)
355 # define CLICK_CFG_YD (0x1 << 3)
356 # define CLICK_CFG_YS (0x1 << 2)
357 # define CLICK_CFG_XD (0x1 << 1)
358 # define CLICK_CFG_XS (0x1 << 0)
359 #define CLICK_SRC 0x39
360 # define CLICK_SRC_IA (0x1 << 6)
361 # define CLICK_SRC_DCLICK (0x1 << 5)
362 # define CLICK_SRC_SCLICK (0x1 << 4)
363 # define CLICK_SRC_SIGN (0x1 << 3)
364 # define CLICK_SRC_Z (0x1 << 2)
365 # define CLICK_SRC_Y (0x1 << 1)
366 # define CLICK_SRC_X (0x1 << 0)
367 #define CLICK_THS 0x3A
368 #define TIME_LIMIT 0x3B
369 #define TIME_LATENCY 0x3C
370 #define TIME_WINDOW 0x3D
371 #define ACT_THS 0x3E
372 #define ACT_DUR 0x3F
373 
377  int drdy_pin_num_a,
378  int drdy_pin_num_g,
379  enum Rotation rotation_a,
380  enum Rotation rotation_g,
381  enum Rotation rotation_gH)
383  , _dev_gyro(std::move(dev_gyro))
384  , _dev_accel(std::move(dev_accel))
385  , _drdy_pin_num_a(drdy_pin_num_a)
386  , _drdy_pin_num_g(drdy_pin_num_g)
387  , _rotation_a(rotation_a)
388  , _rotation_g(rotation_g)
389  , _rotation_gH(rotation_gH)
390 {
391 }
392 
396  enum Rotation rotation_a,
397  enum Rotation rotation_g,
398  enum Rotation rotation_gH)
399 {
400  if (!dev_gyro || !dev_accel) {
401  return nullptr;
402  }
403  AP_InertialSensor_LSM9DS0 *sensor =
404  new AP_InertialSensor_LSM9DS0(_imu, std::move(dev_gyro), std::move(dev_accel),
406  rotation_a, rotation_g, rotation_gH);
407  if (!sensor || !sensor->_init_sensor()) {
408  delete sensor;
409  return nullptr;
410  }
411 
412  return sensor;
413 }
414 
416 {
417  /*
418  * Same semaphore for both since they necessarily share the same bus (with
419  * different CS)
420  */
422 
423  if (_drdy_pin_num_a >= 0) {
425  if (_drdy_pin_a == nullptr) {
426  AP_HAL::panic("LSM9DS0: null accel data-ready GPIO channel\n");
427  }
428 
430  }
431 
432  if (_drdy_pin_num_g >= 0) {
434  if (_drdy_pin_g == nullptr) {
435  AP_HAL::panic("LSM9DS0: null gyro data-ready GPIO channel\n");
436  }
437 
439  }
440 
441  bool success = _hardware_init();
442 
443 #if LSM9DS0_DEBUG
444  _dump_registers();
445 #endif
446 
447  return success;
448 }
449 
451 {
453  return false;
454  }
455 
456  uint8_t tries, whoami;
457 
458  // set flag for reading registers
459  _dev_gyro->set_read_flag(0x80);
460  _dev_accel->set_read_flag(0x80);
461 
464  hal.console->printf("LSM9DS0: unexpected gyro WHOAMI 0x%x\n", (unsigned)whoami_g);
465  goto fail_whoami;
466  }
467 
468  whoami = _register_read_xm(WHO_AM_I_XM);
469  if (whoami != LSM9DS0_XM_WHOAMI) {
470  hal.console->printf("LSM9DS0: unexpected acc/mag WHOAMI 0x%x\n", (unsigned)whoami);
471  goto fail_whoami;
472  }
473 
474  // setup for register checking
477 
478  for (tries = 0; tries < 5; tries++) {
481 
482  _gyro_init();
483  _accel_init();
484 
487 
488  hal.scheduler->delay(10);
489  if (_accel_data_ready() && _gyro_data_ready()) {
490  break;
491  }
492 
493 #if LSM9DS0_DEBUG
494  _dump_registers();
495 #endif
496  }
497  if (tries == 5) {
498  hal.console->printf("Failed to boot LSM9DS0 5 times\n\n");
499  goto fail_tries;
500  }
501 
502  _spi_sem->give();
503 
504  return true;
505 
506 fail_tries:
507 fail_whoami:
508  _spi_sem->give();
509  return false;
510 }
511 
512 
513 /*
514  start the sensor going
515  */
517 {
520 
521  if (whoami_g == LSM9DS0_G_WHOAMI_H) {
523  } else {
525  }
527 
529 
530  /* start the timer process to read samples */
532 }
533 
534 
536 {
537  uint8_t val = 0;
538 
539  _dev_accel->read_registers(reg, &val, 1);
540 
541  return val;
542 }
543 
545 {
546  uint8_t val = 0;
547 
548  _dev_gyro->read_registers(reg, &val, 1);
549 
550  return val;
551 }
552 
553 void AP_InertialSensor_LSM9DS0::_register_write_xm(uint8_t reg, uint8_t val, bool checked)
554 {
555  _dev_accel->write_register(reg, val, checked);
556 }
557 
558 void AP_InertialSensor_LSM9DS0::_register_write_g(uint8_t reg, uint8_t val, bool checked)
559 {
560  _dev_gyro->write_register(reg, val, checked);
561 }
562 
564 {
565  uint8_t retries = 10;
566  while (retries--) {
567  // add retries
568  uint8_t a = _register_read_g(0x05);
569  _register_write_g(0x05, (0x20 | a));
570  if (_register_read_g(0x05) == (a | 0x20)) {
571  return;
572  }
573  }
574  AP_HAL::panic("LSM9DS0_G: Unable to disable I2C");
575 }
576 
578 {
579  uint8_t a = _register_read_xm(0x02);
580  _register_write_xm(0x02, (0x10 | a));
581  a = _register_read_xm(0x02);
582  _register_write_xm(0x02, (0xF7 & a));
583  a = _register_read_xm(0x15);
584  _register_write_xm(0x15, (0x80 | a));
585  a = _register_read_xm(0x02);
586  _register_write_xm(0x02, (0xE7 & a));
587 }
588 
590 {
592  hal.scheduler->delay(1);
593 
599  CTRL_REG1_G_XEN, true);
600  hal.scheduler->delay(1);
601 
602  _register_write_g(CTRL_REG2_G, 0x00, true);
603  hal.scheduler->delay(1);
604 
605  /*
606  * Gyro data ready on DRDY_G
607  */
609  hal.scheduler->delay(1);
610 
613  CTRL_REG4_G_FS_2000DPS, true);
615  hal.scheduler->delay(1);
616 
617  _register_write_g(CTRL_REG5_G, 0x00, true);
618  hal.scheduler->delay(1);
619 }
620 
622 {
624  hal.scheduler->delay(1);
625 
626  _register_write_xm(CTRL_REG0_XM, 0x00, true);
627  hal.scheduler->delay(1);
628 
634  CTRL_REG1_XM_AXEN, true);
635  hal.scheduler->delay(1);
636 
639  CTRL_REG2_XM_AFS_16G, true);
641  hal.scheduler->delay(1);
642 
643  /* Accel data ready on INT1 */
645  hal.scheduler->delay(1);
646 }
647 
649 {
650  /* scales values from datasheet in mdps/digit */
651  switch (scale) {
652  case G_SCALE_245DPS:
653  _gyro_scale = 8.75;
654  break;
655  case G_SCALE_500DPS:
656  _gyro_scale = 17.50;
657  break;
658  case G_SCALE_2000DPS:
659  _gyro_scale = 70;
660  break;
661  }
662 
663  /* convert mdps/digit to dps/digit */
664  _gyro_scale /= 1000;
665  /* convert dps/digit to (rad/s)/digit */
667 }
668 
670 {
671  /*
672  * Possible accelerometer scales (and their register bit settings) are:
673  * 2 g (000), 4g (001), 6g (010) 8g (011), 16g (100). Here's a bit of an
674  * algorithm to calculate g/(ADC tick) based on that 3-bit value:
675  */
676  _accel_scale = (((float) scale + 1.0f) * 2.0f) / 32768.0f;
677  if (scale == A_SCALE_16G) {
678  /* the datasheet shows an exception for +-16G */
679  _accel_scale = 0.000732;
680  }
681  /* convert to G/LSB to (m/s/s)/LSB */
683 }
684 
689 {
690  if (_gyro_data_ready()) {
692  }
693  if (_accel_data_ready()) {
695  }
696 
697  // check next register value for correctness
698  if (!_dev_gyro->check_next_register()) {
700  }
703  }
704 }
705 
707 {
708  if (_drdy_pin_a != nullptr) {
709  return _drdy_pin_a->read() != 0;
710  }
711 
712  uint8_t status = _register_read_xm(STATUS_REG_A);
713  return status & STATUS_REG_A_ZYXADA;
714 }
715 
717 {
718  if (_drdy_pin_g != nullptr) {
719  return _drdy_pin_g->read() != 0;
720  }
721 
722  uint8_t status = _register_read_g(STATUS_REG_G);
723  return status & STATUS_REG_G_ZYXDA;
724 }
725 
727 {
728  struct sensor_raw_data raw_data = { };
729  const uint8_t reg = OUT_X_L_A | 0xC0;
730 
731  if (!_dev_accel->transfer(&reg, 1, (uint8_t *) &raw_data, sizeof(raw_data))) {
732  hal.console->printf("LSM9DS0: error reading accelerometer\n");
733  return;
734  }
735 
736  Vector3f accel_data(raw_data.x, -raw_data.y, -raw_data.z);
737  accel_data *= _accel_scale;
738 
741 }
742 
743 /*
744  * read from the data registers and update filtered data
745  */
747 {
748  struct sensor_raw_data raw_data = { };
749  const uint8_t reg = OUT_X_L_G | 0xC0;
750 
751  if (!_dev_gyro->transfer(&reg, 1, (uint8_t *) &raw_data, sizeof(raw_data))) {
752  hal.console->printf("LSM9DS0: error reading gyroscope\n");
753  return;
754  }
755 
756  Vector3f gyro_data(raw_data.x, -raw_data.y, -raw_data.z);
757 
758  gyro_data *= _gyro_scale;
759 
762 }
763 
765 {
768 
769  return true;
770 }
771 
772 #if LSM9DS0_DEBUG
773 /* dump all config registers - used for debug */
774 void AP_InertialSensor_LSM9DS0::_dump_registers(void)
775 {
776  hal.console->printf("LSM9DS0 registers:\n");
777  hal.console->printf("Gyroscope registers:\n");
778  const uint8_t first = OUT_TEMP_L_XM;
779  const uint8_t last = ACT_DUR;
780  for (uint8_t reg=first; reg<=last; reg++) {
781  uint8_t v = _register_read_g(reg);
782  hal.console->printf("%02x:%02x ", (unsigned)reg, (unsigned)v);
783  if ((reg - (first-1)) % 16 == 0) {
784  hal.console->printf("\n");
785  }
786  }
787  hal.console->printf("\n");
788 
789  hal.console->printf("Accelerometer and Magnetometers registers:\n");
790  for (uint8_t reg=first; reg<=last; reg++) {
791  uint8_t v = _register_read_xm(reg);
792  hal.console->printf("%02x:%02x ", (unsigned)reg, (unsigned)v);
793  if ((reg - (first-1)) % 16 == 0) {
794  hal.console->printf("\n");
795  }
796  }
797  hal.console->printf("\n");
798 
799 }
800 #endif
801 
#define CTRL_REG1_G_PD
void set_gyro_orientation(uint8_t instance, enum Rotation rotation)
#define CTRL_REG4_G_BDU
#define CTRL_REG1_XM_AODR_1600Hz
#define STATUS_REG_G
#define LSM9DS0_G_WHOAMI
void _inc_accel_error_count(uint8_t instance)
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define CTRL_REG5_G
#define CTRL_REG4_G_FS_2000DPS
#define CTRL_REG2_XM_ABW_194Hz
#define CTRL_REG1_G_YEN
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
#define CTRL_REG2_G
uint8_t register_gyro(uint16_t raw_sample_rate_hz, uint32_t id)
#define CTRL_REG2_XM_AFS_16G
#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::SPIDevice > _dev_accel
void _set_accel_scale(accel_scale scale)
#define LSM9DS0_XM_WHOAMI
#define ACT_DUR
#define LSM9DS0_DRY_G_PIN
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_gyro, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_accel, enum Rotation rotation_a=ROTATION_NONE, enum Rotation rotation_g=ROTATION_NONE, enum Rotation rotation_gH=ROTATION_NONE)
Rotation
Definition: rotations.h:27
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
uint32_t get_bus_id_devtype(uint8_t devtype)
Definition: Device.h:255
#define DEG_TO_RAD
Definition: definitions.h:30
bool setup_checked_registers(uint8_t num_regs, uint8_t frequency=10)
Definition: Device.cpp:39
#define CTRL_REG2_XM
#define CTRL_REG1_XM_BDU
virtual void mode(uint8_t output)=0
#define STATUS_REG_A_ZYXADA
AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev_gyro
#define OUT_TEMP_L_XM
virtual void delay(uint16_t ms)=0
#define LSM9DS0_DRY_X_PIN
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
uint8_t register_accel(uint16_t raw_sample_rate_hz, uint32_t id)
void _set_accel_max_abs_offset(uint8_t instance, float offset)
AP_InertialSensor_LSM9DS0(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_gyro, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_accel, int drdy_pin_num_a, int drdy_pin_num_b, enum Rotation rotation_a, enum Rotation rotation_g, enum Rotation rotation_gH)
virtual Semaphore * get_semaphore() override=0
#define CTRL_REG3_XM_P1_DRDYA
#define GRAVITY_MSS
Definition: definitions.h:47
#define f(i)
#define STATUS_REG_A
void _set_gyro_scale(gyro_scale scale)
virtual AP_HAL::DigitalSource * channel(uint16_t n)=0
void _notify_new_gyro_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0)
#define WHO_AM_I_XM
uint64_t micros64()
Definition: system.cpp:162
#define CTRL_REG4_G
#define STATUS_REG_G_ZYXDA
void _rotate_and_correct_gyro(uint8_t instance, Vector3f &gyro)
#define CTRL_REG1_XM
virtual bool give()=0
float v
Definition: Printf.cpp:15
#define CTRL_REG3_G_I2_DRDY
#define CTRL_REG1_G_DR_760Hz_BW_50Hz
#define CTRL_REG1_XM_AZEN
#define WHO_AM_I_G
void _notify_new_accel_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0, bool fsync_set=false)
#define HAL_GPIO_INPUT
Definition: GPIO.h:7
virtual bool set_speed(Device::Speed speed) override=0
#define CTRL_REG1_G
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
#define OUT_X_L_G
AP_HAL::DigitalSource * _drdy_pin_a
#define CTRL_REG1_G_ZEN
#define CTRL_REG0_XM
virtual uint8_t read()=0
void set_read_flag(uint8_t flag)
Definition: Device.h:221
void set_accel_orientation(uint8_t instance, enum Rotation rotation)
AP_HAL::DigitalSource * _drdy_pin_g
AP_HAL::GPIO * gpio
Definition: HAL.h:111
bool check_next_register(void)
Definition: Device.cpp:85
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
#define CTRL_REG3_G
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
void _inc_gyro_error_count(uint8_t instance)
#define OUT_X_L_A
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
#define CTRL_REG1_XM_AYEN
#define CTRL_REG1_G_XEN
void _rotate_and_correct_accel(uint8_t instance, Vector3f &accel)
#define LSM9DS0_G_WHOAMI_H
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
#define CTRL_REG1_XM_AXEN
void _register_write_g(uint8_t reg, uint8_t val, bool checked=false)
void _register_write_xm(uint8_t reg, uint8_t val, bool checked=false)
#define CTRL_REG3_XM