39 #include <px4_platform_common/getopt.h> 40 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp> 46 #if defined(PX4_I2C_OBDEV_ICM20948) || defined(PX4_I2C_BUS_EXPANSION) 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 113 #define BIT_SLEEP 0x40 114 #define BIT_H_RESET 0x80 115 #define MPU_CLK_SEL_AUTO 0x01 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 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 136 #define BITS_ACCEL_CONFIG2_41HZ 0x03 138 #define BIT_RAW_RDY_EN 0x01 139 #define BIT_INT_ANYRD_2CLEAR 0x10 140 #define BIT_INT_BYPASS_EN 0x02 142 #define BIT_I2C_READ_FLAG 0x80 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 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 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 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 169 #define ICM_WHOAMI_20948 0xEA 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 176 #define ICM20948_GYRO_MAX_OUTPUT_RATE ICM20948_ACCEL_MAX_OUTPUT_RATE 177 #define ICM20948_GYRO_DEFAULT_DRIVER_FILTER_FREQ 30 179 #define ICM20948_DEFAULT_ONCHIP_FILTER_FREQ 92 189 #define PX4_I2C_EXT_ICM20948_0 0x68 190 #define PX4_I2C_EXT_ICM20948_1 0x69 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) 208 #define ICMREG_20948_BANK_SEL 0x7F 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) 242 #define ICM_BIT_PWR_MGMT_1_ENABLE 0x00 243 #define ICM_BIT_USER_CTRL_I2C_MST_DISABLE 0x00 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 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 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 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 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 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 286 #define MPU_OR_ICM(m,i) ((_whoami==ICM_WHOAMI_20948) ? i : m) 288 #pragma pack(push, 1) 306 #pragma pack(push, 1) 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) 380 uint8_t _selected_bank{0};
382 unsigned _call_interval{1000};
384 unsigned _dlpf_freq{0};
385 unsigned _dlpf_freq_icm_gyro{0};
386 unsigned _dlpf_freq_icm_accel{0};
388 unsigned _sample_rate{1000};
397 uint8_t _register_wait{0};
398 uint64_t _reset_wait{0};
404 static constexpr
int ICM20948_NUM_CHECKED_REGISTERS{15};
405 static const uint16_t _icm20948_checked_registers[ICM20948_NUM_CHECKED_REGISTERS];
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};
416 float _last_temperature{0.0f};
418 bool check_null_data(uint16_t *
data, uint8_t size);
419 bool check_duplicate(uint8_t *accel_data);
422 uint8_t _last_accel_data[6] {};
423 bool _got_duplicate{
false};
448 int select_register_bank(uint8_t bank);
458 uint16_t read_reg16(
unsigned reg);
470 uint8_t read_reg_range(
unsigned start_reg, uint32_t speed, uint8_t *buf, uint16_t count);
478 void write_reg(
unsigned reg, uint8_t value);
489 void modify_reg(
unsigned reg, uint8_t clearbits, uint8_t setbits);
497 void write_checked_reg(
unsigned reg, uint8_t value);
508 void modify_checked_reg(
unsigned reg, uint8_t clearbits, uint8_t setbits);
516 int set_accel_range(
unsigned max_g);
521 uint16_t
swap16(uint16_t val) {
return (val >> 8) | (val << 8); }
533 void _set_dlpf_filter(uint16_t frequency_hz);
538 void _set_sample_rate(
unsigned desired_sample_rate_hz);
543 void check_registers();
bool is_external()
Get the internal / external state.
perf_counter_t _sample_perf
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.
A set of useful macros for enhanced runtime and compile time error detection and warning suppression...
uint16_t swap16(uint16_t val)
Swap a 16-bit value read from the mpu to native byte order.
int reset(enum LPS22HB_BUS busid)
Reset the driver.
Helper class implementing the magnetometer driver node.
perf_counter_t _duplicates
device::Device * _interface
perf_counter_t _interval_perf
Report conversation within the mpu, including command byte and interrupt status.
void init()
Activates/configures the hardware registers.
Definition of commonly used conversions.
Rotation
Enum for board and external compass rotations.
device::Device * ICM20948_SPI_interface(int bus, uint32_t cs)
virtual bool external() const
device::Device * ICM20948_I2C_interface(int bus, uint32_t address)
#define ICM20948_LOW_BUS_SPEED
Fundamental base class for all physical drivers (I2C, SPI).
PX4Accelerometer _px4_accel
perf_counter_t _good_transfers
void write_reg(unsigned reg, uint8_t value)
perf_counter_t _bad_transfers
perf_counter_t _bad_registers
static constexpr uint8_t _checked_registers[]