TR-mbed 1.0
Loading...
Searching...
No Matches
MPU6050.h
Go to the documentation of this file.
1#ifndef MPU6050_H
2#define MPU6050_H
3
4#include "mbed.h"
5#include "math.h"
6
7#ifndef M_PI
8#define M_PI 3.14159265358979323846
9#endif
10
11// Define registers per MPU6050, Register Map and Descriptions, Rev 4.2, 08/19/2013 6 DOF Motion sensor fusion device
12
13// Invensense Inc., www.invensense.com
14// See also MPU-6050 Register Map and Descriptions, Revision 4.0, RM-MPU-6050A-00, 9/12/2012 for registers not listed in
15// above document; the MPU6050 and MPU 9150 are virtually identical but the latter has an on-board magnetic sensor
16//
17#define XGOFFS_TC 0x00 // Bit 7 PWR_MODE, bits 6:1 XG_OFFS_TC, bit 0 OTP_BNK_VLD
18#define YGOFFS_TC 0x01
19#define ZGOFFS_TC 0x02
20#define X_FINE_GAIN 0x03 // [7:0] fine gain
21#define Y_FINE_GAIN 0x04
22#define Z_FINE_GAIN 0x05
23#define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer
24#define XA_OFFSET_L_TC 0x07
25#define YA_OFFSET_H 0x08
26#define YA_OFFSET_L_TC 0x09
27#define ZA_OFFSET_H 0x0A
28#define ZA_OFFSET_L_TC 0x0B
29#define SELF_TEST_X 0x0D
30#define SELF_TEST_Y 0x0E
31#define SELF_TEST_Z 0x0F
32#define SELF_TEST_A 0x10
33#define XG_OFFS_USRH 0x13 // User-defined trim values for gyroscope; supported in MPU-6050?
34#define XG_OFFS_USRL 0x14
35#define YG_OFFS_USRH 0x15
36#define YG_OFFS_USRL 0x16
37#define ZG_OFFS_USRH 0x17
38#define ZG_OFFS_USRL 0x18
39#define SMPLRT_DIV 0x19
40#define CONFIG 0x1A
41#define GYRO_CONFIG 0x1B
42#define ACCEL_CONFIG 0x1C
43#define FF_THR 0x1D // Free-fall
44#define FF_DUR 0x1E // Free-fall
45#define MOT_THR 0x1F // Motion detection threshold bits [7:0]
46#define MOT_DUR 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms
47#define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0]
48#define ZRMOT_DUR 0x22 // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms
49#define FIFO_EN 0x23
50#define I2C_MST_CTRL 0x24
51#define I2C_SLV0_ADDR 0x25
52#define I2C_SLV0_REG 0x26
53#define I2C_SLV0_CTRL 0x27
54#define I2C_SLV1_ADDR 0x28
55#define I2C_SLV1_REG 0x29
56#define I2C_SLV1_CTRL 0x2A
57#define I2C_SLV2_ADDR 0x2B
58#define I2C_SLV2_REG 0x2C
59#define I2C_SLV2_CTRL 0x2D
60#define I2C_SLV3_ADDR 0x2E
61#define I2C_SLV3_REG 0x2F
62#define I2C_SLV3_CTRL 0x30
63#define I2C_SLV4_ADDR 0x31
64#define I2C_SLV4_REG 0x32
65#define I2C_SLV4_DO 0x33
66#define I2C_SLV4_CTRL 0x34
67#define I2C_SLV4_DI 0x35
68#define I2C_MST_STATUS 0x36
69#define INT_PIN_CFG 0x37
70#define INT_ENABLE 0x38
71#define DMP_INT_STATUS 0x39 // Check DMP interrupt
72#define INT_STATUS 0x3A
73#define ACCEL_XOUT_H 0x3B
74#define ACCEL_XOUT_L 0x3C
75#define ACCEL_YOUT_H 0x3D
76#define ACCEL_YOUT_L 0x3E
77#define ACCEL_ZOUT_H 0x3F
78#define ACCEL_ZOUT_L 0x40
79#define TEMP_OUT_H 0x41
80#define TEMP_OUT_L 0x42
81#define GYRO_XOUT_H 0x43
82#define GYRO_XOUT_L 0x44
83#define GYRO_YOUT_H 0x45
84#define GYRO_YOUT_L 0x46
85#define GYRO_ZOUT_H 0x47
86#define GYRO_ZOUT_L 0x48
87#define EXT_SENS_DATA_00 0x49
88#define EXT_SENS_DATA_01 0x4A
89#define EXT_SENS_DATA_02 0x4B
90#define EXT_SENS_DATA_03 0x4C
91#define EXT_SENS_DATA_04 0x4D
92#define EXT_SENS_DATA_05 0x4E
93#define EXT_SENS_DATA_06 0x4F
94#define EXT_SENS_DATA_07 0x50
95#define EXT_SENS_DATA_08 0x51
96#define EXT_SENS_DATA_09 0x52
97#define EXT_SENS_DATA_10 0x53
98#define EXT_SENS_DATA_11 0x54
99#define EXT_SENS_DATA_12 0x55
100#define EXT_SENS_DATA_13 0x56
101#define EXT_SENS_DATA_14 0x57
102#define EXT_SENS_DATA_15 0x58
103#define EXT_SENS_DATA_16 0x59
104#define EXT_SENS_DATA_17 0x5A
105#define EXT_SENS_DATA_18 0x5B
106#define EXT_SENS_DATA_19 0x5C
107#define EXT_SENS_DATA_20 0x5D
108#define EXT_SENS_DATA_21 0x5E
109#define EXT_SENS_DATA_22 0x5F
110#define EXT_SENS_DATA_23 0x60
111#define MOT_DETECT_STATUS 0x61
112#define I2C_SLV0_DO 0x63
113#define I2C_SLV1_DO 0x64
114#define I2C_SLV2_DO 0x65
115#define I2C_SLV3_DO 0x66
116#define I2C_MST_DELAY_CTRL 0x67
117#define SIGNAL_PATH_RESET 0x68
118#define MOT_DETECT_CTRL 0x69
119#define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP
120#define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode
121#define PWR_MGMT_2 0x6C
122#define DMP_BANK 0x6D // Activates a specific bank in the DMP
123#define DMP_RW_PNT 0x6E // Set read/write pointer to a specific start address in specified DMP bank
124#define DMP_REG 0x6F // Register in DMP from which to read or to which to write
125#define DMP_REG_1 0x70
126#define DMP_REG_2 0x71
127#define FIFO_COUNTH 0x72
128#define FIFO_COUNTL 0x73
129#define FIFO_R_W 0x74
130#define WHO_AM_I_MPU6050 0x75 // Should return 0x68
131
132// Register bits
133#define DATA_RDY_INT 0
134#define I2C_MST_EN 5
135
143
151
153{
154 uint8_t _addr;
155 AccelScale _accelScale;
156 GyroScale _gyroScale;
157 I2C _i2c;
158 InterruptIn _interruptIn;
159 float _accelRes;
160 float _gyroRes;
161 int16_t _accelAdc[3]; // Stores the 16-bit signed accelerometer sensor output
162 int16_t _gyroAdc[3]; // Stores the 16-bit signed gyro sensor output
163 float _gyroBias[3] = { 0 };
164 float _accelBias[3] = { 0 }; // Bias corrections for gyro and accelerometer
165 int16_t _tempInt; // Stores the real internal chip temperature in degrees Celsius
166 float _temp;
167 float _selfTest[6];
168
169 // parameters for 6 DoF sensor fusion calculations
170 const float _gyroError = M_PI * (40.0f / 180.0f); // gyroscope measurement error in rads/s (start at 60 deg/s), then reduce after ~10 s to 3
171 const float _gyroDrift = M_PI * (2.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s)
172 float _beta; // compute beta
173 float _zeta; // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value
174 float _pitch, _yaw, _roll;
175 float _q[4] = { 1.0f, 0.0f, 0.0f, 0.0f }; // vector to hold quaternion
176 void writeReg(uint8_t reg, uint8_t byte);
177 uint8_t readReg(uint8_t reg);
178 void readRegBytes(uint8_t reg, uint8_t len, uint8_t* dest);
179 int16_t* accelADC();
180 int16_t* gyroADC();
181 int16_t tempADC();
182public:
183 float accelData[3]; // Stores the real accelerometer sensor output
184 float& accelX = accelData[0]; // Acceleration liases
185 float& accelY = accelData[1];
186 float& accelZ = accelData[2];
187 float gyroData[3]; // Stores the real gyro sensor output
188 float& gyroX = gyroData[0]; // Gyro aliases
189 float& gyroY = gyroData[1];
190 float& gyroZ = gyroData[2];
191
192 MPU6050
193 (
194 uint8_t addr = 0x68,
195 AccelScale accelScale = AFS_2G,
196 GyroScale gyroScale = GFS_250DPS,
197 PinName sdaPin = I2C_SDA,
198 PinName sclPin = I2C_SCL,
199 PinName interruptInPin = NC
200 );
201 virtual ~MPU6050() { }
202 void rise(Callback<void (void)> func);
203 template<typename T>
204 void rise(T* tptr, void (T:: *mptr) (void));
205 void fall(Callback<void (void)> func);
206 template<typename T>
207 void fall(T* tptr, void (T:: *mptr) (void));
208 bool init();
209 bool dataReady();
210 float* accel();
211 float* gyro();
212 float temp();
213
214 // Configure the motion detection control for low power accelerometer mode
215 void lowPowerAccelOnly();
216 void reset();
217
218 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average
219 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers.
220 void calibrate();
221
222 // Accelerometer and gyroscope self test; check calibration wrt factory settings
223 bool selfTestOK(); // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass
224 void setGain(float beta, float zeta);
225
226 // Implementation of Sebastian Madgwick's "...efficient orientation filter for inertial/magnetic sensor arrays"
227 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details)
228 // which fuses acceleration and rotation rate to produce a quaternion-based estimate of relative
229 // device orientation -- which can be converted to yaw, pitch, and roll.
230 // Useful for stabilizing quadcopters, etc.
231 // The performance of the orientation filter is almost as good as conventional Kalman-based filtering algorithms
232 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz!
233 void madgwickFilter(float deltaT);
234
235 // To compute yaw, pitch and roll after after aplying the madgwickFilter
236 float yaw();
237 float pitch();
238 float roll();
239};
240#endif // MPU6050_H
const CwiseBinaryOp< internal::scalar_zeta_op< Scalar >, const Derived, const DerivedQ > zeta(const EIGEN_CURRENT_STORAGE_BASE_CLASS< DerivedQ > &q) const
Definition ArrayCwiseBinaryOps.h:355
#define I2C_SDA
Definition Chassis.h:22
#define I2C_SCL
Definition Chassis.h:23
AccelScale
Definition MPU6050.h:137
@ AFS_4G
Definition MPU6050.h:139
@ AFS_8G
Definition MPU6050.h:140
@ AFS_2G
Definition MPU6050.h:138
@ AFS_16G
Definition MPU6050.h:141
#define M_PI
Definition MPU6050.h:8
GyroScale
Definition MPU6050.h:145
@ GFS_250DPS
Definition MPU6050.h:146
@ GFS_2000DPS
Definition MPU6050.h:149
@ GFS_1000DPS
Definition MPU6050.h:148
@ GFS_500DPS
Definition MPU6050.h:147
Definition MPU6050.h:153
float yaw()
Calculates yaw in degree.
Definition MPU6050.cpp:787
float accelData[3]
Definition MPU6050.h:183
float * gyro()
Computes gyro.
Definition MPU6050.cpp:647
bool selfTestOK()
Performs accelerometer and gyroscope self test.
Definition MPU6050.cpp:564
void lowPowerAccelOnly()
Configures the motion detection control for low power accelerometer mode.
Definition MPU6050.cpp:326
float & gyroZ
Definition MPU6050.h:190
float & gyroX
Definition MPU6050.h:188
void calibrate()
Calibrates the MPU6050.
Definition MPU6050.cpp:393
float & gyroY
Definition MPU6050.h:189
float gyroData[3]
Definition MPU6050.h:187
float & accelX
Definition MPU6050.h:184
virtual ~MPU6050()
Definition MPU6050.h:201
void reset()
Resets the MPU6050.
Definition MPU6050.cpp:374
bool init()
Initializes the MPU6050.
Definition MPU6050.cpp:131
float pitch()
Calculates pitch in degree.
Definition MPU6050.cpp:804
float & accelY
Definition MPU6050.h:185
float & accelZ
Definition MPU6050.h:186
float * accel()
Computes acceleration.
Definition MPU6050.cpp:629
void madgwickFilter(float deltaT)
Madgwick filter.
Definition MPU6050.cpp:681
float temp()
Definition MPU6050.cpp:311
bool dataReady()
Indicates whether data is available after an interrupt.
Definition MPU6050.cpp:250
float roll()
Claculates roll in degree.
Definition MPU6050.cpp:817
void setGain(float beta, float zeta)
Adjusts filter gain after device is stabilized.
Definition MPU6050.cpp:664
void fall(Callback< void(void)> func)
Definition MPU6050.cpp:65
void rise(Callback< void(void)> func)
Definition MPU6050.cpp:41
Definition benchGeometry.cpp:23