Basic program to get the properly-scaled gyro and accelerometer data from a MPU-6050 6-axis motion sensor. Perform sensor fusion using Sebastian Madgwick's open-source IMU fusion filter. Running on the STM32F401 at 84 MHz achieved sensor fusion filter update rates of 5500 Hz. Additional info at https://github.com/kriswiner/MPU-6050.

Dependencies:   mbed

Committer:
onehorse
Date:
Sun Jun 29 21:41:36 2014 +0000
Revision:
1:cea9d83b8636
Parent:
0:65aa78c10981
first commit

Who changed what in which revision?

UserRevisionLine numberNew contents of line
onehorse 0:65aa78c10981 1
onehorse 0:65aa78c10981 2 /* MPU6050 Basic Example Code
onehorse 0:65aa78c10981 3 by: Kris Winer
onehorse 0:65aa78c10981 4 date: May 1, 2014
onehorse 0:65aa78c10981 5 license: Beerware - Use this code however you'd like. If you
onehorse 0:65aa78c10981 6 find it useful you can buy me a beer some time.
onehorse 0:65aa78c10981 7
onehorse 0:65aa78c10981 8 Demonstrate MPU-6050 basic functionality including initialization, accelerometer trimming, sleep mode functionality as well as
onehorse 0:65aa78c10981 9 parameterizing the register addresses. Added display functions to allow display to on breadboard monitor.
onehorse 0:65aa78c10981 10 No DMP use. We just want to get out the accelerations, temperature, and gyro readings.
onehorse 0:65aa78c10981 11
onehorse 0:65aa78c10981 12 SDA and SCL should have external pull-up resistors (to 3.3V).
onehorse 0:65aa78c10981 13 10k resistors worked for me. They should be on the breakout
onehorse 0:65aa78c10981 14 board.
onehorse 0:65aa78c10981 15
onehorse 0:65aa78c10981 16 Hardware setup:
onehorse 0:65aa78c10981 17 MPU6050 Breakout --------- Arduino
onehorse 0:65aa78c10981 18 3.3V --------------------- 3.3V
onehorse 0:65aa78c10981 19 SDA ----------------------- A4
onehorse 0:65aa78c10981 20 SCL ----------------------- A5
onehorse 0:65aa78c10981 21 GND ---------------------- GND
onehorse 0:65aa78c10981 22
onehorse 0:65aa78c10981 23 Note: The MPU6050 is an I2C sensor and uses the Arduino Wire library.
onehorse 0:65aa78c10981 24 Because the sensor is not 5V tolerant, we are using a 3.3 V 8 MHz Pro Mini or a 3.3 V Teensy 3.1.
onehorse 0:65aa78c10981 25 We have disabled the internal pull-ups used by the Wire library in the Wire.h/twi.c utility file.
onehorse 0:65aa78c10981 26 We are also using the 400 kHz fast I2C mode by setting the TWI_FREQ to 400000L /twi.h utility file.
onehorse 0:65aa78c10981 27 */
onehorse 0:65aa78c10981 28
onehorse 1:cea9d83b8636 29 #include "mbed.h"
onehorse 1:cea9d83b8636 30 #include "MPU6050.h"
onehorse 1:cea9d83b8636 31 #include "N5110.h"
onehorse 0:65aa78c10981 32
onehorse 0:65aa78c10981 33 // Using NOKIA 5110 monochrome 84 x 48 pixel display
onehorse 0:65aa78c10981 34 // pin 9 - Serial clock out (SCLK)
onehorse 0:65aa78c10981 35 // pin 8 - Serial data out (DIN)
onehorse 0:65aa78c10981 36 // pin 7 - Data/Command select (D/C)
onehorse 0:65aa78c10981 37 // pin 5 - LCD chip select (CS)
onehorse 0:65aa78c10981 38 // pin 6 - LCD reset (RST)
onehorse 0:65aa78c10981 39 //Adafruit_PCD8544 display = Adafruit_PCD8544(9, 8, 7, 5, 6);
onehorse 0:65aa78c10981 40
onehorse 1:cea9d83b8636 41 float sum = 0;
onehorse 1:cea9d83b8636 42 uint32_t sumCount = 0;
onehorse 1:cea9d83b8636 43
onehorse 1:cea9d83b8636 44 MPU6050 mpu6050;
onehorse 1:cea9d83b8636 45
onehorse 1:cea9d83b8636 46 Timer t;
onehorse 1:cea9d83b8636 47
onehorse 1:cea9d83b8636 48 Serial pc(USBTX, USBRX); // tx, rx
onehorse 1:cea9d83b8636 49
onehorse 1:cea9d83b8636 50 // VCC, SCE, RST, D/C, MOSI,S CLK, LED
onehorse 1:cea9d83b8636 51 N5110 lcd(PA_8, PB_10, PA_9, PA_6, PA_7, PA_5, PC_7);
onehorse 1:cea9d83b8636 52
onehorse 1:cea9d83b8636 53 int main()
onehorse 1:cea9d83b8636 54 {
onehorse 1:cea9d83b8636 55 pc.baud(9600);
onehorse 0:65aa78c10981 56
onehorse 1:cea9d83b8636 57 //Set up I2C
onehorse 1:cea9d83b8636 58 i2c.frequency(400000); // use fast (400 kHz) I2C
onehorse 1:cea9d83b8636 59
onehorse 1:cea9d83b8636 60 t.start();
onehorse 1:cea9d83b8636 61
onehorse 1:cea9d83b8636 62 lcd.init();
onehorse 1:cea9d83b8636 63 lcd.setBrightness(0.05);
onehorse 1:cea9d83b8636 64
onehorse 1:cea9d83b8636 65
onehorse 1:cea9d83b8636 66 // Read the WHO_AM_I register, this is a good test of communication
onehorse 1:cea9d83b8636 67 uint8_t whoami = mpu6050.readByte(MPU6050_ADDRESS, WHO_AM_I_MPU6050); // Read WHO_AM_I register for MPU-6050
onehorse 1:cea9d83b8636 68 pc.printf("I AM 0x%x\n\r", whoami); pc.printf("I SHOULD BE 0x68\n\r");
onehorse 1:cea9d83b8636 69
onehorse 1:cea9d83b8636 70 if (whoami == 0x68) // WHO_AM_I should always be 0x68
onehorse 1:cea9d83b8636 71 {
onehorse 1:cea9d83b8636 72 pc.printf("MPU6050 is online...");
onehorse 1:cea9d83b8636 73 wait(1);
onehorse 1:cea9d83b8636 74 lcd.clear();
onehorse 1:cea9d83b8636 75 lcd.printString("MPU6050 OK", 0, 0);
onehorse 0:65aa78c10981 76
onehorse 1:cea9d83b8636 77
onehorse 1:cea9d83b8636 78 mpu6050.MPU6050SelfTest(SelfTest); // Start by performing self test and reporting values
onehorse 1:cea9d83b8636 79 pc.printf("x-axis self test: acceleration trim within : "); pc.printf("%f", SelfTest[0]); pc.printf("% of factory value \n\r");
onehorse 1:cea9d83b8636 80 pc.printf("y-axis self test: acceleration trim within : "); pc.printf("%f", SelfTest[1]); pc.printf("% of factory value \n\r");
onehorse 1:cea9d83b8636 81 pc.printf("z-axis self test: acceleration trim within : "); pc.printf("%f", SelfTest[2]); pc.printf("% of factory value \n\r");
onehorse 1:cea9d83b8636 82 pc.printf("x-axis self test: gyration trim within : "); pc.printf("%f", SelfTest[3]); pc.printf("% of factory value \n\r");
onehorse 1:cea9d83b8636 83 pc.printf("y-axis self test: gyration trim within : "); pc.printf("%f", SelfTest[4]); pc.printf("% of factory value \n\r");
onehorse 1:cea9d83b8636 84 pc.printf("z-axis self test: gyration trim within : "); pc.printf("%f", SelfTest[5]); pc.printf("% of factory value \n\r");
onehorse 1:cea9d83b8636 85 wait(1);
onehorse 0:65aa78c10981 86
onehorse 1:cea9d83b8636 87 if(SelfTest[0] < 1.0f && SelfTest[1] < 1.0f && SelfTest[2] < 1.0f && SelfTest[3] < 1.0f && SelfTest[4] < 1.0f && SelfTest[5] < 1.0f)
onehorse 1:cea9d83b8636 88 {
onehorse 1:cea9d83b8636 89 mpu6050.resetMPU6050(); // Reset registers to default in preparation for device calibration
onehorse 1:cea9d83b8636 90 mpu6050.calibrateMPU6050(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers
onehorse 1:cea9d83b8636 91 mpu6050.initMPU6050(); pc.printf("MPU6050 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature
onehorse 0:65aa78c10981 92
onehorse 1:cea9d83b8636 93 lcd.clear();
onehorse 1:cea9d83b8636 94 lcd.printString("MPU6050", 0, 0);
onehorse 1:cea9d83b8636 95 lcd.printString("pass self test", 0, 1);
onehorse 1:cea9d83b8636 96 lcd.printString("initializing", 0, 2);
onehorse 1:cea9d83b8636 97 wait(2);
onehorse 1:cea9d83b8636 98 }
onehorse 1:cea9d83b8636 99 else
onehorse 1:cea9d83b8636 100 {
onehorse 1:cea9d83b8636 101 pc.printf("Device did not the pass self-test!\n\r");
onehorse 0:65aa78c10981 102
onehorse 1:cea9d83b8636 103 lcd.clear();
onehorse 1:cea9d83b8636 104 lcd.printString("MPU6050", 0, 0);
onehorse 1:cea9d83b8636 105 lcd.printString("no pass", 0, 1);
onehorse 1:cea9d83b8636 106 lcd.printString("self test", 0, 2);
onehorse 1:cea9d83b8636 107 }
onehorse 1:cea9d83b8636 108 }
onehorse 1:cea9d83b8636 109 else
onehorse 1:cea9d83b8636 110 {
onehorse 1:cea9d83b8636 111 pc.printf("Could not connect to MPU6050: \n\r");
onehorse 1:cea9d83b8636 112 pc.printf("%#x \n", whoami);
onehorse 1:cea9d83b8636 113
onehorse 1:cea9d83b8636 114 lcd.clear();
onehorse 1:cea9d83b8636 115 lcd.printString("MPU6050", 0, 0);
onehorse 1:cea9d83b8636 116 lcd.printString("no connection", 0, 1);
onehorse 1:cea9d83b8636 117 lcd.printString("0x", 0, 2); lcd.setXYAddress(20, 2); lcd.printChar(whoami);
onehorse 1:cea9d83b8636 118
onehorse 1:cea9d83b8636 119 while(1) ; // Loop forever if communication doesn't happen
onehorse 0:65aa78c10981 120 }
onehorse 0:65aa78c10981 121
onehorse 0:65aa78c10981 122
onehorse 0:65aa78c10981 123
onehorse 1:cea9d83b8636 124 while(1) {
onehorse 0:65aa78c10981 125
onehorse 1:cea9d83b8636 126 // If data ready bit set, all data registers have new data
onehorse 1:cea9d83b8636 127 if(mpu6050.readByte(MPU6050_ADDRESS, INT_STATUS) & 0x01) { // check if data ready interrupt
onehorse 1:cea9d83b8636 128 mpu6050.readAccelData(accelCount); // Read the x/y/z adc values
onehorse 1:cea9d83b8636 129 mpu6050.getAres();
onehorse 0:65aa78c10981 130
onehorse 0:65aa78c10981 131 // Now we'll calculate the accleration value into actual g's
onehorse 0:65aa78c10981 132 ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set
onehorse 0:65aa78c10981 133 ay = (float)accelCount[1]*aRes - accelBias[1];
onehorse 0:65aa78c10981 134 az = (float)accelCount[2]*aRes - accelBias[2];
onehorse 0:65aa78c10981 135
onehorse 1:cea9d83b8636 136 mpu6050.readGyroData(gyroCount); // Read the x/y/z adc values
onehorse 1:cea9d83b8636 137 mpu6050.getGres();
onehorse 0:65aa78c10981 138
onehorse 0:65aa78c10981 139 // Calculate the gyro value into actual degrees per second
onehorse 1:cea9d83b8636 140 gx = (float)gyroCount[0]*gRes; // - gyroBias[0]; // get actual gyro value, this depends on scale being set
onehorse 1:cea9d83b8636 141 gy = (float)gyroCount[1]*gRes; // - gyroBias[1];
onehorse 1:cea9d83b8636 142 gz = (float)gyroCount[2]*gRes; // - gyroBias[2];
onehorse 0:65aa78c10981 143
onehorse 1:cea9d83b8636 144 tempCount = mpu6050.readTempData(); // Read the x/y/z adc values
onehorse 0:65aa78c10981 145 temperature = (tempCount) / 340. + 36.53; // Temperature in degrees Centigrade
onehorse 0:65aa78c10981 146 }
onehorse 0:65aa78c10981 147
onehorse 0:65aa78c10981 148 Now = t.read_us();
onehorse 1:cea9d83b8636 149 deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update
onehorse 0:65aa78c10981 150 lastUpdate = Now;
onehorse 1:cea9d83b8636 151
onehorse 1:cea9d83b8636 152 sum += deltat;
onehorse 1:cea9d83b8636 153 sumCount++;
onehorse 1:cea9d83b8636 154
onehorse 0:65aa78c10981 155 if(lastUpdate - firstUpdate > 10000000.0f) {
onehorse 1:cea9d83b8636 156 beta = 0.04; // decrease filter gain after stabilized
onehorse 1:cea9d83b8636 157 zeta = 0.015; // increasey bias drift gain after stabilized
onehorse 0:65aa78c10981 158 }
onehorse 1:cea9d83b8636 159
onehorse 0:65aa78c10981 160 // Pass gyro rate as rad/s
onehorse 1:cea9d83b8636 161 mpu6050.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f);
onehorse 0:65aa78c10981 162
onehorse 0:65aa78c10981 163 // Serial print and/or display at 0.5 s rate independent of data rates
onehorse 0:65aa78c10981 164 delt_t = t.read_ms() - count;
onehorse 0:65aa78c10981 165 if (delt_t > 500) { // update LCD once per half-second independent of read rate
onehorse 1:cea9d83b8636 166
onehorse 1:cea9d83b8636 167 pc.printf("ax = %f", 1000*ax);
onehorse 1:cea9d83b8636 168 pc.printf(" ay = %f", 1000*ay);
onehorse 1:cea9d83b8636 169 pc.printf(" az = %f mg\n\r", 1000*az);
onehorse 0:65aa78c10981 170
onehorse 1:cea9d83b8636 171 pc.printf("gx = %f", gx);
onehorse 1:cea9d83b8636 172 pc.printf(" gy = %f", gy);
onehorse 1:cea9d83b8636 173 pc.printf(" gz = %f deg/s\n\r", gz);
onehorse 1:cea9d83b8636 174
onehorse 1:cea9d83b8636 175 pc.printf(" temperature = %f C\n\r", temperature);
onehorse 0:65aa78c10981 176
onehorse 1:cea9d83b8636 177 pc.printf("q0 = %f\n\r", q[0]);
onehorse 1:cea9d83b8636 178 pc.printf("q1 = %f\n\r", q[1]);
onehorse 1:cea9d83b8636 179 pc.printf("q2 = %f\n\r", q[2]);
onehorse 1:cea9d83b8636 180 pc.printf("q3 = %f\n\r", q[3]);
onehorse 1:cea9d83b8636 181
onehorse 1:cea9d83b8636 182 lcd.clear();
onehorse 1:cea9d83b8636 183 lcd.printString("MPU6050", 0, 0);
onehorse 1:cea9d83b8636 184 lcd.printString("x y z", 0, 1);
onehorse 1:cea9d83b8636 185 lcd.setXYAddress(0, 2); lcd.printChar((char)(1000*ax));
onehorse 1:cea9d83b8636 186 lcd.setXYAddress(20, 2); lcd.printChar((char)(1000*ay));
onehorse 1:cea9d83b8636 187 lcd.setXYAddress(40, 2); lcd.printChar((char)(1000*az)); lcd.printString("mg", 66, 2);
onehorse 1:cea9d83b8636 188
onehorse 0:65aa78c10981 189
onehorse 0:65aa78c10981 190 // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation.
onehorse 0:65aa78c10981 191 // In this coordinate system, the positive z-axis is down toward Earth.
onehorse 0:65aa78c10981 192 // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise.
onehorse 0:65aa78c10981 193 // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative.
onehorse 0:65aa78c10981 194 // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll.
onehorse 0:65aa78c10981 195 // These arise from the definition of the homogeneous rotation matrix constructed from quaternions.
onehorse 0:65aa78c10981 196 // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be
onehorse 0:65aa78c10981 197 // applied in the correct order which for this configuration is yaw, pitch, and then roll.
onehorse 0:65aa78c10981 198 // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links.
onehorse 0:65aa78c10981 199 yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]);
onehorse 0:65aa78c10981 200 pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
onehorse 0:65aa78c10981 201 roll = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]);
onehorse 0:65aa78c10981 202 pitch *= 180.0f / PI;
onehorse 0:65aa78c10981 203 yaw *= 180.0f / PI;
onehorse 0:65aa78c10981 204 roll *= 180.0f / PI;
onehorse 0:65aa78c10981 205
onehorse 1:cea9d83b8636 206 // pc.printf("Yaw, Pitch, Roll: \n\r");
onehorse 1:cea9d83b8636 207 // pc.printf("%f", yaw);
onehorse 1:cea9d83b8636 208 // pc.printf(", ");
onehorse 1:cea9d83b8636 209 // pc.printf("%f", pitch);
onehorse 1:cea9d83b8636 210 // pc.printf(", ");
onehorse 1:cea9d83b8636 211 // pc.printf("%f\n\r", roll);
onehorse 1:cea9d83b8636 212 // pc.printf("average rate = "); pc.printf("%f", (sumCount/sum)); pc.printf(" Hz\n\r");
onehorse 0:65aa78c10981 213
onehorse 1:cea9d83b8636 214 pc.printf("Yaw, Pitch, Roll: %f %f %f\n\r", yaw, pitch, roll);
onehorse 1:cea9d83b8636 215 pc.printf("average rate = %f\n\r", (float) sumCount/sum);
onehorse 1:cea9d83b8636 216
onehorse 1:cea9d83b8636 217 myled= !myled;
onehorse 1:cea9d83b8636 218 count = t.read_ms();
onehorse 1:cea9d83b8636 219 sum = 0;
onehorse 1:cea9d83b8636 220 sumCount = 0;
onehorse 0:65aa78c10981 221 }
onehorse 0:65aa78c10981 222 }
onehorse 1:cea9d83b8636 223
onehorse 1:cea9d83b8636 224 }