PX4 Firmware
PX4 Autopilot Software http://px4.io
icm20948.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 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 #pragma once
35 
38 #include <lib/ecl/geo/geo.h>
39 #include <px4_platform_common/getopt.h>
40 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
43 
44 #include "ICM20948_mag.h"
45 
46 #if defined(PX4_I2C_OBDEV_ICM20948) || defined(PX4_I2C_BUS_EXPANSION)
47 # define USE_I2C
48 #endif
49 
50 
51 // ICM20948 registers
52 #define MPUREG_WHOAMI 0x75
53 #define MPUREG_SMPLRT_DIV 0x19
54 #define MPUREG_CONFIG 0x1A
55 #define MPUREG_GYRO_CONFIG 0x1B
56 #define MPUREG_ACCEL_CONFIG 0x1C
57 #define MPUREG_ACCEL_CONFIG2 0x1D
58 #define MPUREG_LPACCEL_ODR 0x1E
59 #define MPUREG_WOM_THRESH 0x1F
60 #define MPUREG_FIFO_EN 0x23
61 #define MPUREG_I2C_MST_CTRL 0x24
62 #define MPUREG_I2C_SLV0_ADDR 0x25
63 #define MPUREG_I2C_SLV0_REG 0x26
64 #define MPUREG_I2C_SLV0_CTRL 0x27
65 #define MPUREG_I2C_SLV1_ADDR 0x28
66 #define MPUREG_I2C_SLV1_REG 0x29
67 #define MPUREG_I2C_SLV1_CTRL 0x2A
68 #define MPUREG_I2C_SLV2_ADDR 0x2B
69 #define MPUREG_I2C_SLV2_REG 0x2C
70 #define MPUREG_I2C_SLV2_CTRL 0x2D
71 #define MPUREG_I2C_SLV3_ADDR 0x2E
72 #define MPUREG_I2C_SLV3_REG 0x2F
73 #define MPUREG_I2C_SLV3_CTRL 0x30
74 #define MPUREG_I2C_SLV4_ADDR 0x31
75 #define MPUREG_I2C_SLV4_REG 0x32
76 #define MPUREG_I2C_SLV4_DO 0x33
77 #define MPUREG_I2C_SLV4_CTRL 0x34
78 #define MPUREG_I2C_SLV4_DI 0x35
79 #define MPUREG_I2C_MST_STATUS 0x36
80 #define MPUREG_INT_PIN_CFG 0x37
81 #define MPUREG_INT_ENABLE 0x38
82 #define MPUREG_INT_STATUS 0x3A
83 #define MPUREG_ACCEL_XOUT_H 0x3B
84 #define MPUREG_ACCEL_XOUT_L 0x3C
85 #define MPUREG_ACCEL_YOUT_H 0x3D
86 #define MPUREG_ACCEL_YOUT_L 0x3E
87 #define MPUREG_ACCEL_ZOUT_H 0x3F
88 #define MPUREG_ACCEL_ZOUT_L 0x40
89 #define MPUREG_TEMP_OUT_H 0x41
90 #define MPUREG_TEMP_OUT_L 0x42
91 #define MPUREG_GYRO_XOUT_H 0x43
92 #define MPUREG_GYRO_XOUT_L 0x44
93 #define MPUREG_GYRO_YOUT_H 0x45
94 #define MPUREG_GYRO_YOUT_L 0x46
95 #define MPUREG_GYRO_ZOUT_H 0x47
96 #define MPUREG_GYRO_ZOUT_L 0x48
97 #define MPUREG_EXT_SENS_DATA_00 0x49
98 #define MPUREG_I2C_SLV0_D0 0x63
99 #define MPUREG_I2C_SLV1_D0 0x64
100 #define MPUREG_I2C_SLV2_D0 0x65
101 #define MPUREG_I2C_SLV3_D0 0x66
102 #define MPUREG_I2C_MST_DELAY_CTRL 0x67
103 #define MPUREG_SIGNAL_PATH_RESET 0x68
104 #define MPUREG_MOT_DETECT_CTRL 0x69
105 #define MPUREG_USER_CTRL 0x6A
106 #define MPUREG_PWR_MGMT_1 0x6B
107 #define MPUREG_PWR_MGMT_2 0x6C
108 #define MPUREG_FIFO_COUNTH 0x72
109 #define MPUREG_FIFO_COUNTL 0x73
110 #define MPUREG_FIFO_R_W 0x74
111 
112 // Configuration bits ICM20948
113 #define BIT_SLEEP 0x40
114 #define BIT_H_RESET 0x80
115 #define MPU_CLK_SEL_AUTO 0x01
116 
117 #define BITS_GYRO_ST_X 0x80
118 #define BITS_GYRO_ST_Y 0x40
119 #define BITS_GYRO_ST_Z 0x20
120 #define BITS_FS_250DPS 0x00
121 #define BITS_FS_500DPS 0x08
122 #define BITS_FS_1000DPS 0x10
123 #define BITS_FS_2000DPS 0x18
124 #define BITS_FS_MASK 0x18
125 
126 #define BITS_DLPF_CFG_250HZ 0x00
127 #define BITS_DLPF_CFG_184HZ 0x01
128 #define BITS_DLPF_CFG_92HZ 0x02
129 #define BITS_DLPF_CFG_41HZ 0x03
130 #define BITS_DLPF_CFG_20HZ 0x04
131 #define BITS_DLPF_CFG_10HZ 0x05
132 #define BITS_DLPF_CFG_5HZ 0x06
133 #define BITS_DLPF_CFG_3600HZ 0x07
134 #define BITS_DLPF_CFG_MASK 0x07
135 
136 #define BITS_ACCEL_CONFIG2_41HZ 0x03
137 
138 #define BIT_RAW_RDY_EN 0x01
139 #define BIT_INT_ANYRD_2CLEAR 0x10
140 #define BIT_INT_BYPASS_EN 0x02
141 
142 #define BIT_I2C_READ_FLAG 0x80
143 
144 #define BIT_I2C_SLV0_NACK 0x01
145 #define BIT_I2C_FIFO_EN 0x40
146 #define BIT_I2C_MST_EN 0x20
147 #define BIT_I2C_IF_DIS 0x10
148 #define BIT_FIFO_RST 0x04
149 #define BIT_I2C_MST_RST 0x02
150 #define BIT_SIG_COND_RST 0x01
151 
152 #define BIT_I2C_SLV0_EN 0x80
153 #define BIT_I2C_SLV0_BYTE_SW 0x40
154 #define BIT_I2C_SLV0_REG_DIS 0x20
155 #define BIT_I2C_SLV0_REG_GRP 0x10
156 
157 #define BIT_I2C_MST_MULT_MST_EN 0x80
158 #define BIT_I2C_MST_WAIT_FOR_ES 0x40
159 #define BIT_I2C_MST_SLV_3_FIFO_EN 0x20
160 #define BIT_I2C_MST_P_NSR 0x10
161 #define BITS_I2C_MST_CLOCK_258HZ 0x08
162 #define BITS_I2C_MST_CLOCK_400HZ 0x0D
163 
164 #define BIT_I2C_SLV0_DLY_EN 0x01
165 #define BIT_I2C_SLV1_DLY_EN 0x02
166 #define BIT_I2C_SLV2_DLY_EN 0x04
167 #define BIT_I2C_SLV3_DLY_EN 0x08
168 
169 #define ICM_WHOAMI_20948 0xEA
170 
171 #define ICM20948_ACCEL_DEFAULT_RATE 1000
172 #define ICM20948_ACCEL_MAX_OUTPUT_RATE 280
173 #define ICM20948_ACCEL_DEFAULT_DRIVER_FILTER_FREQ 30
174 #define ICM20948_GYRO_DEFAULT_RATE 1000
175 /* rates need to be the same between accel and gyro */
176 #define ICM20948_GYRO_MAX_OUTPUT_RATE ICM20948_ACCEL_MAX_OUTPUT_RATE
177 #define ICM20948_GYRO_DEFAULT_DRIVER_FILTER_FREQ 30
178 
179 #define ICM20948_DEFAULT_ONCHIP_FILTER_FREQ 92
180 
181 
182 // ICM20948 registers and data
183 
184 /*
185  * ICM20948 I2C address LSB can be switched by the chip's AD0 pin, thus is device dependent.
186  * Noting this down for now. Here GPS uses 0x69. To support a device implementing the second
187  * address, probably an additional MPU_DEVICE_TYPE is the way to go.
188  */
189 #define PX4_I2C_EXT_ICM20948_0 0x68
190 #define PX4_I2C_EXT_ICM20948_1 0x69
191 
192 /*
193  * ICM20948 uses register banks. Register 127 (0x7F) is used to switch between 4 banks.
194  * There's room in the upper address byte below the port speed setting to code in the
195  * used bank. This is a bit more efficient, already in use for the speed setting and more
196  * in one place than a solution with a lookup table for address/bank pairs.
197  */
198 
199 #define BANK0 0x0000
200 #define BANK1 0x0100
201 #define BANK2 0x0200
202 #define BANK3 0x0300
203 
204 #define BANK_REG_MASK 0x0300
205 #define REG_BANK(r) (((r) & BANK_REG_MASK)>>4)
206 #define REG_ADDRESS(r) ((r) & ~BANK_REG_MASK)
207 
208 #define ICMREG_20948_BANK_SEL 0x7F
209 
210 #define ICMREG_20948_WHOAMI (0x00 | BANK0)
211 #define ICMREG_20948_USER_CTRL (0x03 | BANK0)
212 #define ICMREG_20948_PWR_MGMT_1 (0x06 | BANK0)
213 #define ICMREG_20948_PWR_MGMT_2 (0x07 | BANK0)
214 #define ICMREG_20948_INT_PIN_CFG (0x0F | BANK0)
215 #define ICMREG_20948_INT_ENABLE (0x10 | BANK0)
216 #define ICMREG_20948_INT_ENABLE_1 (0x11 | BANK0)
217 #define ICMREG_20948_ACCEL_XOUT_H (0x2D | BANK0)
218 #define ICMREG_20948_INT_ENABLE_2 (0x12 | BANK0)
219 #define ICMREG_20948_INT_ENABLE_3 (0x13 | BANK0)
220 #define ICMREG_20948_EXT_SLV_SENS_DATA_00 (0x3B | BANK0)
221 #define ICMREG_20948_GYRO_SMPLRT_DIV (0x00 | BANK2)
222 #define ICMREG_20948_GYRO_CONFIG_1 (0x01 | BANK2)
223 #define ICMREG_20948_GYRO_CONFIG_2 (0x02 | BANK2)
224 #define ICMREG_20948_ACCEL_SMPLRT_DIV_1 (0x10 | BANK2)
225 #define ICMREG_20948_ACCEL_SMPLRT_DIV_2 (0x11 | BANK2)
226 #define ICMREG_20948_ACCEL_CONFIG (0x14 | BANK2)
227 #define ICMREG_20948_ACCEL_CONFIG_2 (0x15 | BANK2)
228 #define ICMREG_20948_I2C_MST_CTRL (0x01 | BANK3)
229 #define ICMREG_20948_I2C_SLV0_ADDR (0x03 | BANK3)
230 #define ICMREG_20948_I2C_SLV0_REG (0x04 | BANK3)
231 #define ICMREG_20948_I2C_SLV0_CTRL (0x05 | BANK3)
232 #define ICMREG_20948_I2C_SLV0_DO (0x06 | BANK3)
233 
234 
235 
236 /*
237 * ICM20948 register bits
238 * Most of the regiser set values from ICM20948 have the same
239 * meaning on ICM20948. The exceptions and values not already
240 * defined for ICM20948 are defined below
241 */
242 #define ICM_BIT_PWR_MGMT_1_ENABLE 0x00
243 #define ICM_BIT_USER_CTRL_I2C_MST_DISABLE 0x00
244 
245 #define ICM_BITS_GYRO_DLPF_CFG_197HZ 0x01
246 #define ICM_BITS_GYRO_DLPF_CFG_151HZ 0x09
247 #define ICM_BITS_GYRO_DLPF_CFG_119HZ 0x11
248 #define ICM_BITS_GYRO_DLPF_CFG_51HZ 0x19
249 #define ICM_BITS_GYRO_DLPF_CFG_23HZ 0x21
250 #define ICM_BITS_GYRO_DLPF_CFG_11HZ 0x29
251 #define ICM_BITS_GYRO_DLPF_CFG_5HZ 0x31
252 #define ICM_BITS_GYRO_DLPF_CFG_361HZ 0x39
253 #define ICM_BITS_GYRO_DLPF_CFG_MASK 0x39
254 
255 #define ICM_BITS_GYRO_FS_SEL_250DPS 0x00
256 #define ICM_BITS_GYRO_FS_SEL_500DPS 0x02
257 #define ICM_BITS_GYRO_FS_SEL_1000DPS 0x04
258 #define ICM_BITS_GYRO_FS_SEL_2000DPS 0x06
259 #define ICM_BITS_GYRO_FS_SEL_MASK 0x06
260 
261 #define ICM_BITS_ACCEL_DLPF_CFG_246HZ 0x09
262 #define ICM_BITS_ACCEL_DLPF_CFG_111HZ 0x11
263 #define ICM_BITS_ACCEL_DLPF_CFG_50HZ 0x19
264 #define ICM_BITS_ACCEL_DLPF_CFG_23HZ 0x21
265 #define ICM_BITS_ACCEL_DLPF_CFG_11HZ 0x29
266 #define ICM_BITS_ACCEL_DLPF_CFG_5HZ 0x31
267 #define ICM_BITS_ACCEL_DLPF_CFG_473HZ 0x39
268 #define ICM_BITS_ACCEL_DLPF_CFG_MASK 0x39
269 
270 #define ICM_BITS_ACCEL_FS_SEL_250DPS 0x00
271 #define ICM_BITS_ACCEL_FS_SEL_500DPS 0x02
272 #define ICM_BITS_ACCEL_FS_SEL_1000DPS 0x04
273 #define ICM_BITS_ACCEL_FS_SEL_2000DPS 0x06
274 #define ICM_BITS_ACCEL_FS_SEL_MASK 0x06
275 
276 #define ICM_BITS_DEC3_CFG_4 0x00
277 #define ICM_BITS_DEC3_CFG_8 0x01
278 #define ICM_BITS_DEC3_CFG_16 0x10
279 #define ICM_BITS_DEC3_CFG_32 0x11
280 #define ICM_BITS_DEC3_CFG_MASK 0x11
281 
282 #define ICM_BITS_I2C_MST_CLOCK_370KHZ 0x00
283 #define ICM_BITS_I2C_MST_CLOCK_400HZ 0x07 // recommended by datasheet for 400kHz target clock
284 
285 
286 #define MPU_OR_ICM(m,i) ((_whoami==ICM_WHOAMI_20948) ? i : m)
287 
288 #pragma pack(push, 1)
289 /**
290  * Report conversation within the mpu, including command byte and
291  * interrupt status.
292  */
293 struct ICMReport {
294  uint8_t accel_x[2];
295  uint8_t accel_y[2];
296  uint8_t accel_z[2];
297  uint8_t gyro_x[2];
298  uint8_t gyro_y[2];
299  uint8_t gyro_z[2];
300  uint8_t temp[2];
302 };
303 #pragma pack(pop)
304 
305 
306 #pragma pack(push, 1)
307 /**
308  * Report conversation within the mpu, including command byte and
309  * interrupt status.
310  */
311 struct MPUReport {
312  uint8_t cmd;
313  uint8_t status;
314  uint8_t accel_x[2];
315  uint8_t accel_y[2];
316  uint8_t accel_z[2];
317  uint8_t temp[2];
318  uint8_t gyro_x[2];
319  uint8_t gyro_y[2];
320  uint8_t gyro_z[2];
321  struct ak09916_regs mag;
322 };
323 #pragma pack(pop)
324 
325 /*
326  The ICM20948 can only handle high bus speeds on the sensor and
327  interrupt status registers. All other registers have a maximum 1MHz
328  Communication with all registers of the device is performed using either
329  I2C at 400kHz or SPI at 1MHz. For applications requiring faster communications,
330  the sensor and interrupt registers may be read using SPI at 20MHz
331  */
332 #define ICM20948_LOW_BUS_SPEED 0
333 #define ICM20948_HIGH_BUS_SPEED 0x8000
334 #define ICM20948_REG_MASK 0x00FF
335 # define ICM20948_IS_HIGH_SPEED(r) ((r) & ICM20948_HIGH_BUS_SPEED)
336 # define ICM20948_REG(r) ((r) & ICM20948_REG_MASK)
337 # define ICM20948_SET_SPEED(r, s) ((r)|(s))
338 # define ICM20948_HIGH_SPEED_OP(r) ICM20948_SET_SPEED((r), ICM20948_HIGH_BUS_SPEED)
339 # define ICM20948_LOW_SPEED_OP(r) ((r) &~ICM20948_HIGH_BUS_SPEED)
340 
341 /* interface factories */
342 extern device::Device *ICM20948_SPI_interface(int bus, uint32_t cs);
343 extern device::Device *ICM20948_I2C_interface(int bus, uint32_t address);
344 extern int ICM20948_probe(device::Device *dev);
345 
346 typedef device::Device *(*ICM20948_constructor)(int, uint32_t);
347 
348 class ICM20948_mag;
349 
350 class ICM20948 : public px4::ScheduledWorkItem
351 {
352 public:
353  ICM20948(device::Device *interface, device::Device *mag_interface, enum Rotation rotation);
354  virtual ~ICM20948();
355 
356  virtual int init();
357  uint8_t get_whoami() { return _whoami; }
358 
359  /**
360  * Diagnostics - print some basic information about the driver.
361  */
362  void print_info();
363 
364 protected:
366  uint8_t _whoami{0}; /** whoami result */
367 
368  virtual int probe();
369 
370  friend class ICM20948_mag;
371 
372  void Run() override;
373 
374 private:
375 
378 
380  uint8_t _selected_bank{0}; /* Remember selected memory bank to avoid polling / setting on each read/write */
381 
382  unsigned _call_interval{1000};
383 
384  unsigned _dlpf_freq{0};
385  unsigned _dlpf_freq_icm_gyro{0};
386  unsigned _dlpf_freq_icm_accel{0};
387 
388  unsigned _sample_rate{1000};
389 
396 
397  uint8_t _register_wait{0};
398  uint64_t _reset_wait{0};
399 
400  // this is used to support runtime checking of key
401  // configuration registers to detect SPI bus errors and sensor
402  // reset
403 
404  static constexpr int ICM20948_NUM_CHECKED_REGISTERS{15};
405  static const uint16_t _icm20948_checked_registers[ICM20948_NUM_CHECKED_REGISTERS];
406 
407  const uint16_t *_checked_registers{nullptr};
408 
409  uint8_t _checked_values[ICM20948_NUM_CHECKED_REGISTERS] {};
410  uint8_t _checked_bad[ICM20948_NUM_CHECKED_REGISTERS] {};
411  unsigned _checked_next{0};
412  unsigned _num_checked_registers{0};
413 
414 
415  // last temperature reading for print_info()
416  float _last_temperature{0.0f};
417 
418  bool check_null_data(uint16_t *data, uint8_t size);
419  bool check_duplicate(uint8_t *accel_data);
420 
421  // keep last accel reading for duplicate detection
422  uint8_t _last_accel_data[6] {};
423  bool _got_duplicate{false};
424 
425  void start();
426  void stop();
427  int reset();
428 
429  /**
430  * Resets the main chip (excluding the magnetometer if any).
431  */
432  int reset_mpu();
433 
434  /**
435  * Fetch measurements from the sensor and update the report buffers.
436  */
437  void measure();
438 
439  /**
440  * Select a register bank in ICM20948
441  *
442  * Only actually switches if the remembered bank is different from the
443  * requested one
444  *
445  * @param The index of the register bank to switch to (0-3)
446  * @return Error code
447  */
448  int select_register_bank(uint8_t bank);
449 
450  /**
451  * Read a register from the mpu
452  *
453  * @param The register to read.
454  * @param The bus speed to read with.
455  * @return The value that was read.
456  */
457  uint8_t read_reg(unsigned reg, uint32_t speed = ICM20948_LOW_BUS_SPEED);
458  uint16_t read_reg16(unsigned reg);
459 
460 
461  /**
462  * Read a register range from the mpu
463  *
464  * @param The start address to read from.
465  * @param The bus speed to read with.
466  * @param The address of the target data buffer.
467  * @param The count of bytes to be read.
468  * @return The value that was read.
469  */
470  uint8_t read_reg_range(unsigned start_reg, uint32_t speed, uint8_t *buf, uint16_t count);
471 
472  /**
473  * Write a register in the mpu
474  *
475  * @param reg The register to write.
476  * @param value The new value to write.
477  */
478  void write_reg(unsigned reg, uint8_t value);
479 
480  /**
481  * Modify a register in the mpu
482  *
483  * Bits are cleared before bits are set.
484  *
485  * @param reg The register to modify.
486  * @param clearbits Bits in the register to clear.
487  * @param setbits Bits in the register to set.
488  */
489  void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
490 
491  /**
492  * Write a register in the mpu, updating _checked_values
493  *
494  * @param reg The register to write.
495  * @param value The new value to write.
496  */
497  void write_checked_reg(unsigned reg, uint8_t value);
498 
499  /**
500  * Modify a checked register in the mpu
501  *
502  * Bits are cleared before bits are set.
503  *
504  * @param reg The register to modify.
505  * @param clearbits Bits in the register to clear.
506  * @param setbits Bits in the register to set.
507  */
508  void modify_checked_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
509 
510  /**
511  * Set the mpu measurement range.
512  *
513  * @param max_g The maximum G value the range must support.
514  * @return OK if the value can be supported, -ERANGE otherwise.
515  */
516  int set_accel_range(unsigned max_g);
517 
518  /**
519  * Swap a 16-bit value read from the mpu to native byte order.
520  */
521  uint16_t swap16(uint16_t val) { return (val >> 8) | (val << 8); }
522 
523  /**
524  * Get the internal / external state
525  *
526  * @return true if the sensor is not on the main MCU board
527  */
528  bool is_external() { return _interface->external(); }
529 
530  /*
531  set low pass filter frequency
532  */
533  void _set_dlpf_filter(uint16_t frequency_hz);
534 
535  /*
536  set sample rate (approximate) - 1kHz to 5Hz
537  */
538  void _set_sample_rate(unsigned desired_sample_rate_hz);
539 
540  /*
541  check that key registers still have the right value
542  */
543  void check_registers();
544 };
bool is_external()
Get the internal / external state.
Definition: icm20948.h:528
perf_counter_t _sample_perf
Definition: icm20948.h:390
int ICM20948_probe(device::Device *dev)
Definition of geo / math functions to perform geodesic calculations.
uint8_t read_reg(unsigned reg)
Report conversation within the mpu, including command byte and interrupt status.
Definition: icm20948.h:293
struct ak09916_regs mag
Definition: icm20948.h:301
A set of useful macros for enhanced runtime and compile time error detection and warning suppression...
PX4Gyroscope _px4_gyro
Definition: icm20948.h:377
ICM20948_mag _mag
Definition: icm20948.h:379
uint16_t swap16(uint16_t val)
Swap a 16-bit value read from the mpu to native byte order.
Definition: icm20948.h:521
int reset(enum LPS22HB_BUS busid)
Reset the driver.
Helper class implementing the magnetometer driver node.
Definition: ICM20948_mag.h:111
static void stop()
Definition: dataman.cpp:1491
uint8_t gyro_x[2]
Definition: icm20948.h:297
perf_counter_t _duplicates
Definition: icm20948.h:395
uint8_t get_whoami()
Definition: icm20948.h:357
uint8_t status
Definition: icm20948.h:313
uint8_t temp[2]
Definition: icm20948.h:300
device::Device * _interface
Definition: icm20948.h:365
perf_counter_t _interval_perf
Definition: icm20948.h:391
Report conversation within the mpu, including command byte and interrupt status.
Definition: icm20948.h:311
Header common to all counters.
void init()
Activates/configures the hardware registers.
Definition of commonly used conversions.
uint8_t cmd
Definition: icm20948.h:312
uint8_t gyro_z[2]
Definition: icm20948.h:299
uint8_t gyro_y[2]
Definition: icm20948.h:298
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
uint8_t * data
Definition: dataman.cpp:149
device::Device * ICM20948_SPI_interface(int bus, uint32_t cs)
static int start()
Definition: dataman.cpp:1452
virtual bool external() const
Definition: Device.hpp:237
uint8_t accel_y[2]
Definition: icm20948.h:295
device::Device * ICM20948_I2C_interface(int bus, uint32_t address)
#define ICM20948_LOW_BUS_SPEED
Definition: icm20948.h:332
Fundamental base class for all physical drivers (I2C, SPI).
Definition: Device.hpp:65
PX4Accelerometer _px4_accel
Definition: icm20948.h:376
uint8_t accel_x[2]
Definition: icm20948.h:294
perf_counter_t _good_transfers
Definition: icm20948.h:394
void write_reg(unsigned reg, uint8_t value)
perf_counter_t _bad_transfers
Definition: icm20948.h:392
perf_counter_t _bad_registers
Definition: icm20948.h:393
uint8_t accel_z[2]
Definition: icm20948.h:296
static constexpr uint8_t _checked_registers[]
Definition: FXAS21002C.cpp:178