mpu6000.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017, James Jackson
3  *
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright notice, this
10  * list of conditions and the following disclaimer.
11  *
12  * * Redistributions in binary form must reproduce the above copyright notice,
13  * this list of conditions and the following disclaimer in the documentation
14  * and/or other materials provided with the distribution.
15  *
16  * * Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived from
18  * this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #ifndef MPU6000_H
33 #define MPU6000_H
34 
35 #include "spi.h"
36 #include "system.h"
37 
38 // Bits
39 #define MPU_BIT_SLEEP 0x40
40 #define MPU_BIT_H_RESET 0x80
41 #define MPU_BITS_CLKSEL 0x07
42 #define MPU_CLK_SEL_PLLGYROX 0x01
43 #define MPU_CLK_SEL_PLLGYROZ 0x03
44 #define MPU_EXT_SYNC_GYROX 0x02
45 #define MPU_BITS_FS_250DPS 0x00
46 #define MPU_BITS_FS_500DPS 0x08
47 #define MPU_BITS_FS_1000DPS 0x10
48 #define MPU_BITS_FS_2000DPS 0x18
49 #define MPU_BITS_FS_2G 0x00
50 #define MPU_BITS_FS_4G 0x08
51 #define MPU_BITS_FS_8G 0x10
52 #define MPU_BITS_FS_16G 0x18
53 #define MPU_BITS_FS_MASK 0x18
54 #define MPU_BITS_DLPF_CFG_256HZ 0x00
55 #define MPU_BITS_DLPF_CFG_188HZ 0x01
56 #define MPU_BITS_DLPF_CFG_98HZ 0x02
57 #define MPU_BITS_DLPF_CFG_42HZ 0x03
58 #define MPU_BITS_DLPF_CFG_20HZ 0x04
59 #define MPU_BITS_DLPF_CFG_10HZ 0x05
60 #define MPU_BITS_DLPF_CFG_5HZ 0x06
61 #define MPU_BITS_DLPF_CFG_2100HZ_NOLPF 0x07
62 #define MPU_BITS_DLPF_CFG_MASK 0x07
63 #define MPU_BIT_INT_ANYRD_2CLEAR 0x10
64 #define MPU_BIT_RAW_RDY_EN 0x01
65 #define MPU_BIT_I2C_IF_DIS 0x10
66 #define MPU_BIT_INT_STATUS_DATA 0x01
67 #define MPU_BIT_GYRO 0x04
68 #define MPU_BIT_ACC 0x02
69 #define MPU_BIT_TEMP 0x01
70 
71 #define MPU_RA_XG_OFFS_TC 0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD
72 #define MPU_RA_YG_OFFS_TC 0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD
73 #define MPU_RA_ZG_OFFS_TC 0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD
74 #define MPU_RA_X_FINE_GAIN 0x03 //[7:0] X_FINE_GAIN
75 #define MPU_RA_Y_FINE_GAIN 0x04 //[7:0] Y_FINE_GAIN
76 #define MPU_RA_Z_FINE_GAIN 0x05 //[7:0] Z_FINE_GAIN
77 #define MPU_RA_XA_OFFS_H 0x06 //[15:0] XA_OFFS
78 #define MPU_RA_XA_OFFS_L_TC 0x07
79 #define MPU_RA_YA_OFFS_H 0x08 //[15:0] YA_OFFS
80 #define MPU_RA_YA_OFFS_L_TC 0x09
81 #define MPU_RA_ZA_OFFS_H 0x0A //[15:0] ZA_OFFS
82 #define MPU_RA_ZA_OFFS_L_TC 0x0B
83 #define MPU_RA_PRODUCT_ID 0x0C // Product ID Register
84 #define MPU_RA_XG_OFFS_USRH 0x13 //[15:0] XG_OFFS_USR
85 #define MPU_RA_XG_OFFS_USRL 0x14
86 #define MPU_RA_YG_OFFS_USRH 0x15 //[15:0] YG_OFFS_USR
87 #define MPU_RA_YG_OFFS_USRL 0x16
88 #define MPU_RA_ZG_OFFS_USRH 0x17 //[15:0] ZG_OFFS_USR
89 #define MPU_RA_ZG_OFFS_USRL 0x18
90 #define MPU_RA_SMPLRT_DIV 0x19
91 #define MPU_RA_CONFIG 0x1A
92 #define MPU_RA_GYRO_CONFIG 0x1B
93 #define MPU_RA_ACCEL_CONFIG 0x1C
94 #define MPU_RA_FF_THR 0x1D
95 #define MPU_RA_FF_DUR 0x1E
96 #define MPU_RA_MOT_THR 0x1F
97 #define MPU_RA_MOT_DUR 0x20
98 #define MPU_RA_ZRMOT_THR 0x21
99 #define MPU_RA_ZRMOT_DUR 0x22
100 #define MPU_RA_FIFO_EN 0x23
101 #define MPU_RA_I2C_MST_CTRL 0x24
102 #define MPU_RA_I2C_SLV0_ADDR 0x25
103 #define MPU_RA_I2C_SLV0_REG 0x26
104 #define MPU_RA_I2C_SLV0_CTRL 0x27
105 #define MPU_RA_I2C_SLV1_ADDR 0x28
106 #define MPU_RA_I2C_SLV1_REG 0x29
107 #define MPU_RA_I2C_SLV1_CTRL 0x2A
108 #define MPU_RA_I2C_SLV2_ADDR 0x2B
109 #define MPU_RA_I2C_SLV2_REG 0x2C
110 #define MPU_RA_I2C_SLV2_CTRL 0x2D
111 #define MPU_RA_I2C_SLV3_ADDR 0x2E
112 #define MPU_RA_I2C_SLV3_REG 0x2F
113 #define MPU_RA_I2C_SLV3_CTRL 0x30
114 #define MPU_RA_I2C_SLV4_ADDR 0x31
115 #define MPU_RA_I2C_SLV4_REG 0x32
116 #define MPU_RA_I2C_SLV4_DO 0x33
117 #define MPU_RA_I2C_SLV4_CTRL 0x34
118 #define MPU_RA_I2C_SLV4_DI 0x35
119 #define MPU_RA_I2C_MST_STATUS 0x36
120 #define MPU_RA_INT_PIN_CFG 0x37
121 #define MPU_RA_INT_ENABLE 0x38
122 #define MPU_RA_DMP_INT_STATUS 0x39
123 #define MPU_RA_INT_STATUS 0x3A
124 #define MPU_RA_ACCEL_XOUT_H 0x3B
125 #define MPU_RA_ACCEL_XOUT_L 0x3C
126 #define MPU_RA_ACCEL_YOUT_H 0x3D
127 #define MPU_RA_ACCEL_YOUT_L 0x3E
128 #define MPU_RA_ACCEL_ZOUT_H 0x3F
129 #define MPU_RA_ACCEL_ZOUT_L 0x40
130 #define MPU_RA_TEMP_OUT_H 0x41
131 #define MPU_RA_TEMP_OUT_L 0x42
132 #define MPU_RA_GYRO_XOUT_H 0x43
133 #define MPU_RA_GYRO_XOUT_L 0x44
134 #define MPU_RA_GYRO_YOUT_H 0x45
135 #define MPU_RA_GYRO_YOUT_L 0x46
136 #define MPU_RA_GYRO_ZOUT_H 0x47
137 #define MPU_RA_GYRO_ZOUT_L 0x48
138 #define MPU_RA_EXT_SENS_DATA_00 0x49
139 #define MPU_RA_MOT_DETECT_STATUS 0x61
140 #define MPU_RA_I2C_SLV0_DO 0x63
141 #define MPU_RA_I2C_SLV1_DO 0x64
142 #define MPU_RA_I2C_SLV2_DO 0x65
143 #define MPU_RA_I2C_SLV3_DO 0x66
144 #define MPU_RA_I2C_MST_DELAY_CTRL 0x67
145 #define MPU_RA_SIGNAL_PATH_RESET 0x68
146 #define MPU_RA_MOT_DETECT_CTRL 0x69
147 #define MPU_RA_USER_CTRL 0x6A
148 #define MPU_RA_PWR_MGMT_1 0x6B
149 #define MPU_RA_PWR_MGMT_2 0x6C
150 #define MPU_RA_BANK_SEL 0x6D
151 #define MPU_RA_MEM_START_ADDR 0x6E
152 #define MPU_RA_MEM_R_W 0x6F
153 #define MPU_RA_DMP_CFG_1 0x70
154 #define MPU_RA_DMP_CFG_2 0x71
155 #define MPU_RA_FIFO_COUNTH 0x72
156 #define MPU_RA_FIFO_COUNTL 0x73
157 #define MPU_RA_FIFO_R_W 0x74
158 #define MPU_RA_WHO_AM_I 0x75
159 
160 class MPU6000
161 {
162 public:
163  void init(SPI *spi_drv);
164 
165  void read(float *accel_data, float *gyro_data, float *temp_data, uint64_t *time_us);
166  void data_transfer_callback();
167  void exti_cb();
168  bool new_data();
169  inline bool is_initialized() { return spi; }
170 
171 private:
172  void write(uint8_t reg, uint8_t data);
173  bool new_data_ = false;
174  uint64_t imu_timestamp_ = 0;
175  SPI *spi{nullptr};
179  float gyro_scale_;
180  float acc_[3];
181  float gyro_[3];
182  float temp_;
183 };
184 
185 #endif
Definition: spi.h:37
void exti_cb()
Definition: mpu6000.cpp:130
GPIO exti_
Definition: mpu6000.h:176
bool new_data_
Definition: mpu6000.h:173
GPIO cs_
Definition: mpu6000.h:177
volatile int16_t temp_data
Definition: accelgyro.c:31
float accel_scale_
Definition: mpu6000.h:178
void init(SPI *spi_drv)
Definition: mpu6000.cpp:52
static volatile uint8_t reg
Definition: drv_i2c.c:96
volatile int16_t accel_data[3]
Definition: accelgyro.c:29
float gyro_scale_
Definition: mpu6000.h:179
uint64_t imu_timestamp_
Definition: mpu6000.h:174
bool is_initialized()
Definition: mpu6000.h:169
SPI * spi
Definition: mpu6000.h:175
void data_transfer_callback()
Definition: mpu6000.cpp:104
float temp_
Definition: mpu6000.h:182
Definition: gpio.h:37
float gyro_[3]
Definition: mpu6000.h:181
void read(float *accel_data, float *gyro_data, float *temp_data, uint64_t *time_us)
Definition: mpu6000.cpp:118
float acc_[3]
Definition: mpu6000.h:180
void write(uint8_t reg, uint8_t data)
Definition: mpu6000.cpp:43
volatile int16_t gyro_data[3]
Definition: accelgyro.c:30
bool new_data()
Definition: mpu6000.cpp:137


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:47