PX4 Firmware
PX4 Autopilot Software http://px4.io
MPU6000.hpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2016 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 mpu6000.cpp
36  *
37  * Driver for the Invensense MPU6000, MPU6050, ICM20608, and ICM20602 connected via
38  * SPI or I2C.
39  *
40  * When the device is on the SPI bus the hrt is used to provide thread of
41  * execution to the driver.
42  *
43  * When the device is on the I2C bus a work queue is used provide thread of
44  * execution to the driver.
45  *
46  * The I2C code is only included in the build if USE_I2C is defined by the
47  * existance of any of PX4_I2C_MPU6050_ADDR, PX4_I2C_MPU6000_ADDR
48  * PX4_I2C_ICM_20608_G_ADDR in the board_config.h file.
49  *
50  * The command line option -T 6000|20608|20602 (default 6000) selects between
51  * MPU60x0, ICM20608G, or ICM20602G;
52  *
53  * @author Andrew Tridgell
54  * @author Pat Hickey
55  * @author David Sidrane
56  */
57 
61 #include <lib/drivers/device/i2c.h>
62 #include <lib/drivers/device/spi.h>
63 #include <lib/ecl/geo/geo.h>
64 #include <lib/perf/perf_counter.h>
65 #include <px4_platform_common/getopt.h>
66 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
67 #include <systemlib/conversions.h>
68 #include <systemlib/px4_macros.h>
69 
70 
71 /*
72  we set the timer interrupt to run a bit faster than the desired
73  sample rate and then throw away duplicates by comparing
74  accelerometer values. This time reduction is enough to cope with
75  worst case timing jitter due to other timers
76 
77  I2C bus is running at 100 kHz Transaction time is 2.163ms
78  I2C bus is running at 400 kHz (304 kHz actual) Transaction time
79  is 583 us
80 
81  */
82 
83 #pragma once
84 
85 #if defined(PX4_I2C_MPU6050_ADDR) || \
86  defined(PX4_I2C_MPU6000_ADDR) || \
87  defined(PX4_I2C_ICM_20608_G_ADDR)
88 # define USE_I2C
89 #endif
90 
96 };
97 
98 #define DIR_READ 0x80
99 #define DIR_WRITE 0x00
100 
101 // MPU 6000 registers
102 #define MPUREG_WHOAMI 0x75
103 #define MPUREG_SMPLRT_DIV 0x19
104 #define MPUREG_CONFIG 0x1A
105 #define MPUREG_GYRO_CONFIG 0x1B
106 #define MPUREG_ACCEL_CONFIG 0x1C
107 #define MPUREG_FIFO_EN 0x23
108 #define MPUREG_INT_PIN_CFG 0x37
109 #define MPUREG_INT_ENABLE 0x38
110 #define MPUREG_INT_STATUS 0x3A
111 #define MPUREG_ACCEL_XOUT_H 0x3B
112 #define MPUREG_ACCEL_XOUT_L 0x3C
113 #define MPUREG_ACCEL_YOUT_H 0x3D
114 #define MPUREG_ACCEL_YOUT_L 0x3E
115 #define MPUREG_ACCEL_ZOUT_H 0x3F
116 #define MPUREG_ACCEL_ZOUT_L 0x40
117 #define MPUREG_TEMP_OUT_H 0x41
118 #define MPUREG_TEMP_OUT_L 0x42
119 #define MPUREG_GYRO_XOUT_H 0x43
120 #define MPUREG_GYRO_XOUT_L 0x44
121 #define MPUREG_GYRO_YOUT_H 0x45
122 #define MPUREG_GYRO_YOUT_L 0x46
123 #define MPUREG_GYRO_ZOUT_H 0x47
124 #define MPUREG_GYRO_ZOUT_L 0x48
125 #define MPUREG_USER_CTRL 0x6A
126 #define MPUREG_PWR_MGMT_1 0x6B
127 #define MPUREG_PWR_MGMT_2 0x6C
128 #define MPUREG_FIFO_COUNTH 0x72
129 #define MPUREG_FIFO_COUNTL 0x73
130 #define MPUREG_FIFO_R_W 0x74
131 #define MPUREG_PRODUCT_ID 0x0C
132 #define MPUREG_TRIM1 0x0D
133 #define MPUREG_TRIM2 0x0E
134 #define MPUREG_TRIM3 0x0F
135 #define MPUREG_TRIM4 0x10
136 #define MPU_GYRO_DLPF_CFG_256HZ_NOLPF2 0x00 // delay: 0.98ms
137 #define MPU_GYRO_DLPF_CFG_188HZ 0x01 // delay: 1.9ms
138 #define MPU_GYRO_DLPF_CFG_98HZ 0x02 // delay: 2.8ms
139 #define MPU_GYRO_DLPF_CFG_42HZ 0x03 // delay: 4.8ms
140 #define MPU_GYRO_DLPF_CFG_20HZ 0x04 // delay: 8.3ms
141 #define MPU_GYRO_DLPF_CFG_10HZ 0x05 // delay: 13.4ms
142 #define MPU_GYRO_DLPF_CFG_5HZ 0x06 // delay: 18.6ms
143 #define MPU_GYRO_DLPF_CFG_2100HZ_NOLPF 0x07
144 #define MPU_DLPF_CFG_MASK 0x07
145 
146 // Configuration bits MPU 3000 and MPU 6000 (not revised)?
147 #define BIT_SLEEP 0x40
148 #define BIT_H_RESET 0x80
149 #define BITS_CLKSEL 0x07
150 #define MPU_CLK_SEL_PLLGYROX 0x01
151 #define MPU_CLK_SEL_PLLGYROZ 0x03
152 #define MPU_EXT_SYNC_GYROX 0x02
153 #define BITS_GYRO_ST_X 0x80
154 #define BITS_GYRO_ST_Y 0x40
155 #define BITS_GYRO_ST_Z 0x20
156 #define BITS_FS_250DPS 0x00
157 #define BITS_FS_500DPS 0x08
158 #define BITS_FS_1000DPS 0x10
159 #define BITS_FS_2000DPS 0x18
160 #define BITS_FS_MASK 0x18
161 #define BIT_INT_ANYRD_2CLEAR 0x10
162 #define BIT_RAW_RDY_EN 0x01
163 #define BIT_I2C_IF_DIS 0x10
164 #define BIT_INT_STATUS_DATA 0x01
165 
166 #define MPU_WHOAMI_6000 0x68
167 #define ICM_WHOAMI_20602 0x12
168 #define ICM_WHOAMI_20608 0xaf
169 #define ICM_WHOAMI_20689 0x98
170 
171 // ICM2608 specific registers
172 
173 #define ICMREG_ACCEL_CONFIG2 0x1D
174 #define ICM_ACC_DLPF_CFG_1046HZ_NOLPF 0x00
175 #define ICM_ACC_DLPF_CFG_218HZ 0x01
176 #define ICM_ACC_DLPF_CFG_99HZ 0x02
177 #define ICM_ACC_DLPF_CFG_44HZ 0x03
178 #define ICM_ACC_DLPF_CFG_21HZ 0x04
179 #define ICM_ACC_DLPF_CFG_10HZ 0x05
180 #define ICM_ACC_DLPF_CFG_5HZ 0x06
181 #define ICM_ACC_DLPF_CFG_420HZ 0x07
182 /* this is an undocumented register which
183  if set incorrectly results in getting a 2.7m/s/s offset
184  on the Y axis of the accelerometer
185 */
186 #define MPUREG_ICM_UNDOC1 0x11
187 #define MPUREG_ICM_UNDOC1_VALUE 0xc9
188 
189 // Product ID Description for ICM20602
190 // Read From device
191 
192 #define ICM20602_REV_01 1
193 #define ICM20602_REV_02 2
194 
195 // Product ID Description for ICM20608
196 
197 #define ICM20608_REV_FF 0xff // In the past, was thought to be not returning a value. But seem repeatable.
198 
199 // Product ID Description for ICM20689
200 
201 #define ICM20689_REV_FE 0xfe
202 #define ICM20689_REV_03 0x03
203 #define ICM20689_REV_04 0x04
204 
205 // Product ID Description for MPU6000
206 // high 4 bits low 4 bits
207 // Product Name Product Revision
208 #define MPU6000ES_REV_C4 0x14
209 #define MPU6000ES_REV_C5 0x15
210 #define MPU6000ES_REV_D6 0x16
211 #define MPU6000ES_REV_D7 0x17
212 #define MPU6000ES_REV_D8 0x18
213 #define MPU6000_REV_C4 0x54
214 #define MPU6000_REV_C5 0x55
215 #define MPU6000_REV_D6 0x56
216 #define MPU6000_REV_D7 0x57
217 #define MPU6000_REV_D8 0x58
218 #define MPU6000_REV_D9 0x59
219 #define MPU6000_REV_D10 0x5A
220 #define MPU6050_REV_D8 0x28 // TODO:Need verification
221 
222 #define MPU6000_ACCEL_DEFAULT_RANGE_G 16
223 
224 #define MPU6000_GYRO_DEFAULT_RANGE_G 8
225 #define MPU6000_GYRO_DEFAULT_RATE 1000
226 
227 
228 #define MPU6000_DEFAULT_ONCHIP_FILTER_FREQ 98
229 
230 #pragma pack(push, 1)
231 /**
232  * Report conversation within the MPU6000, including command byte and
233  * interrupt status.
234  */
235 struct MPUReport {
236  uint8_t cmd;
237  uint8_t status;
238  uint8_t accel_x[2];
239  uint8_t accel_y[2];
240  uint8_t accel_z[2];
241  uint8_t temp[2];
242  uint8_t gyro_x[2];
243  uint8_t gyro_y[2];
244  uint8_t gyro_z[2];
245 };
246 #pragma pack(pop)
247 
248 #define MPU_MAX_READ_BUFFER_SIZE (sizeof(MPUReport) + 1)
249 #define MPU_MAX_WRITE_BUFFER_SIZE (2)
250 /*
251  The MPU6000 can only handle high bus speeds on the sensor and
252  interrupt status registers. All other registers have a maximum 1MHz
253  Communication with all registers of the device is performed using either
254  I2C at 400kHz or SPI at 1MHz. For applications requiring faster communications,
255  the sensor and interrupt registers may be read using SPI at 20MHz
256  */
257 #define MPU6000_LOW_BUS_SPEED 0
258 #define MPU6000_HIGH_BUS_SPEED 0x8000
259 # define MPU6000_IS_HIGH_SPEED(r) ((r) & MPU6000_HIGH_BUS_SPEED)
260 # define MPU6000_REG(r) ((r) &~MPU6000_HIGH_BUS_SPEED)
261 # define MPU6000_SET_SPEED(r, s) ((r)|(s))
262 # define MPU6000_HIGH_SPEED_OP(r) MPU6000_SET_SPEED((r), MPU6000_HIGH_BUS_SPEED)
263 # define MPU6000_LOW_SPEED_OP(r) MPU6000_REG((r))
264 
265 /* interface factories */
266 extern device::Device *MPU6000_SPI_interface(int bus, int device_type, bool external_bus);
267 extern device::Device *MPU6000_I2C_interface(int bus, int device_type, bool external_bus);
268 extern int MPU6000_probe(device::Device *dev, int device_type);
269 
270 typedef device::Device *(*MPU6000_constructor)(int, int, bool);
271 
272 
273 #define MPU6000_TIMER_REDUCTION 200
274 
283 };
284 
285 class MPU6000 : public px4::ScheduledWorkItem
286 {
287 public:
288  MPU6000(device::Device *interface, enum Rotation rotation, int device_type);
289 
290  virtual ~MPU6000();
291 
292  virtual int init();
293 
294  /**
295  * Diagnostics - print some basic information about the driver.
296  */
297  void print_info();
298 
299  void print_registers();
300 
301 #ifndef CONSTRAINED_FLASH
302  /**
303  * Test behaviour against factory offsets
304  *
305  * @return 0 on success, 1 on failure
306  */
307  int factory_self_test();
308 #endif
309 
310  // deliberately cause a sensor error
311  void test_error();
312 
313  /**
314  * Start automatic measurement.
315  */
316  void start();
317 
318  /**
319  * Reset chip.
320  *
321  * Resets the chip and measurements ranges, but not scale and offset.
322  */
323  int reset();
324 
325 protected:
327 
328  virtual int probe();
329 
330 private:
331 
332  void Run() override;
333 
335  uint8_t _product{0}; /** product code */
336 
337  unsigned _call_interval{1000};
338 
341 
342  unsigned _sample_rate{1000};
343 
349 
350  uint8_t _register_wait{0};
351  uint64_t _reset_wait{0};
352 
353  // this is used to support runtime checking of key
354  // configuration registers to detect SPI bus errors and sensor
355  // reset
356  static constexpr int MPU6000_CHECKED_PRODUCT_ID_INDEX = 0;
357  static constexpr int MPU6000_NUM_CHECKED_REGISTERS = 10;
358 
359  static constexpr uint8_t _checked_registers[MPU6000_NUM_CHECKED_REGISTERS] {
370  };
371 
372  uint8_t _checked_values[MPU6000_NUM_CHECKED_REGISTERS];
373  uint8_t _checked_next{0};
374 
375  // use this to avoid processing measurements when in factory
376  // self test
377  volatile bool _in_factory_test{false};
378 
379  // keep last accel reading for duplicate detection
380  uint16_t _last_accel[3] {};
381  bool _got_duplicate{false};
382 
383  /**
384  * Stop automatic measurement.
385  */
386  void stop();
387 
388  /**
389  * is_icm_device
390  */
391  bool is_icm_device() { return !is_mpu_device(); }
392  /**
393  * is_mpu_device
394  */
395  bool is_mpu_device() { return _device_type == MPU_DEVICE_TYPE_MPU6000; }
396 
397  /**
398  * Fetch measurements from the sensor and update the report buffers.
399  */
400  int measure();
401 
402  /**
403  * Read a register from the MPU6000
404  *
405  * @param The register to read.
406  * @return The value that was read.
407  */
408  uint8_t read_reg(unsigned reg, uint32_t speed = MPU6000_LOW_BUS_SPEED);
409  uint16_t read_reg16(unsigned reg);
410 
411 
412  /**
413  * Write a register in the MPU6000
414  *
415  * @param reg The register to write.
416  * @param value The new value to write.
417  */
418  int write_reg(unsigned reg, uint8_t value);
419 
420  /**
421  * Modify a register in the MPU6000
422  *
423  * Bits are cleared before bits are set.
424  *
425  * @param reg The register to modify.
426  * @param clearbits Bits in the register to clear.
427  * @param setbits Bits in the register to set.
428  */
429  void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
430 
431  /**
432  * Write a register in the MPU6000, updating _checked_values
433  *
434  * @param reg The register to write.
435  * @param value The new value to write.
436  */
437  void write_checked_reg(unsigned reg, uint8_t value);
438 
439  /**
440  * Set the MPU6000 measurement range.
441  *
442  * @param max_g The maximum G value the range must support.
443  * @return OK if the value can be supported, -ERANGE otherwise.
444  */
445  int set_accel_range(unsigned max_g);
446 
447  /*
448  set low pass filter frequency
449  */
450  void _set_dlpf_filter(uint16_t frequency_hz);
451  void _set_icm_acc_dlpf_filter(uint16_t frequency_hz);
452 
453  /*
454  set sample rate (approximate) - 1kHz to 5Hz
455  */
456  void _set_sample_rate(unsigned desired_sample_rate_hz);
457 
458  /*
459  check that key registers still have the right value
460  */
461  void check_registers(void);
462 
463  /* do not allow to copy this class due to pointer data members */
464  MPU6000(const MPU6000 &);
465  MPU6000 operator=(const MPU6000 &);
466 
467 };
device::Device * MPU6000_SPI_interface(int bus, int device_type, bool external_bus)
perf_counter_t _reset_retries
Definition: MPU6000.hpp:347
#define MPUREG_GYRO_CONFIG
Definition: MPU6000.hpp:105
Definition of geo / math functions to perform geodesic calculations.
bool is_mpu_device()
is_mpu_device
Definition: MPU6000.hpp:395
#define MPUREG_CONFIG
Definition: MPU6000.hpp:104
#define MPUREG_USER_CTRL
Definition: MPU6000.hpp:125
int _device_type
Definition: MPU6000.hpp:334
#define MPU6000_LOW_BUS_SPEED
Definition: MPU6000.hpp:257
A set of useful macros for enhanced runtime and compile time error detection and warning suppression...
#define MPUREG_PWR_MGMT_1
Definition: MPU6000.hpp:126
int reset(enum LPS22HB_BUS busid)
Reset the driver.
#define MPUREG_SMPLRT_DIV
Definition: MPU6000.hpp:103
uint8_t accel_z[2]
Definition: icm20948.h:316
static void stop()
Definition: dataman.cpp:1491
perf_counter_t _sample_perf
Definition: MPU6000.hpp:344
bool is_icm_device()
is_icm_device
Definition: MPU6000.hpp:391
uint8_t temp[2]
Definition: icm20948.h:317
uint8_t status
Definition: icm20948.h:313
uint8_t accel_y[2]
Definition: icm20948.h:315
Vector rotation library.
#define MPUREG_PRODUCT_ID
Definition: MPU6000.hpp:131
PX4Accelerometer _px4_accel
Definition: MPU6000.hpp:339
void test_error()
trigger an error
Report conversation within the mpu, including command byte and interrupt status.
Definition: icm20948.h:311
Header common to all counters.
#define MPUREG_ACCEL_CONFIG
Definition: MPU6000.hpp:106
void init()
Activates/configures the hardware registers.
perf_counter_t _bad_registers
Definition: MPU6000.hpp:346
Definition of commonly used conversions.
uint8_t cmd
Definition: icm20948.h:312
uint8_t gyro_z[2]
Definition: icm20948.h:320
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
perf_counter_t _bad_transfers
Definition: MPU6000.hpp:345
int MPU6000_probe(device::Device *dev, int device_type)
PX4Gyroscope _px4_gyro
Definition: MPU6000.hpp:340
#define MPUREG_INT_PIN_CFG
Definition: MPU6000.hpp:108
device::Device * MPU6000_I2C_interface(int bus, int device_type, bool external_bus)
uint8_t accel_x[2]
Definition: icm20948.h:314
static int start()
Definition: dataman.cpp:1452
uint8_t gyro_y[2]
Definition: icm20948.h:319
perf_counter_t _duplicates
Definition: MPU6000.hpp:348
Fundamental base class for all physical drivers (I2C, SPI).
Definition: Device.hpp:65
device::Device * _interface
Definition: MPU6000.hpp:326
#define MPUREG_ICM_UNDOC1
Definition: MPU6000.hpp:186
#define MPUREG_INT_ENABLE
Definition: MPU6000.hpp:109
MPU_DEVICE_TYPE
Definition: MPU6000.hpp:91
MPU6000_BUS
Definition: MPU6000.hpp:275
uint8_t gyro_x[2]
Definition: icm20948.h:318
static constexpr uint8_t _checked_registers[]
Definition: FXAS21002C.cpp:178
Performance measuring tools.
Base class for devices connected via I2C.