Basic program to obtain properly-scaled gyro, accelerometer, and magnetometer data from the MPU-9150 9-axis motion sensor. Nine-axis sensor fusion with Sebastian Madgwick's and Mahony's open-source sensor fusion filters running on an STM32F401RE Nucleo board at 84 MHz achieve sensor fusion filter update rates of ~5000 Hz. Additional info at https://github.com/kriswiner/STM32F401.

Dependencies:   ST_401_84MHZ mbed

Committer:
onehorse
Date:
Sun Jun 29 22:48:08 2014 +0000
Revision:
0:39935bb3c1a1
Basic program to get properly-scaled gyro, accelerometer, and magnetometer data from the MPU9150 9-axis motion sensor. Sensor fusion is performed using Madgwick and Mahony open-source MARG fusion filters.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
onehorse 0:39935bb3c1a1 1 /* MPU9150 Basic Example Code
onehorse 0:39935bb3c1a1 2 by: Kris Winer
onehorse 0:39935bb3c1a1 3 date: April 1, 2014
onehorse 0:39935bb3c1a1 4 license: Beerware - Use this code however you'd like. If you
onehorse 0:39935bb3c1a1 5 find it useful you can buy me a beer some time.
onehorse 0:39935bb3c1a1 6
onehorse 0:39935bb3c1a1 7 Demonstrate basic MPU-9150 functionality including parameterizing the register addresses, initializing the sensor,
onehorse 0:39935bb3c1a1 8 getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to
onehorse 0:39935bb3c1a1 9 allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and
onehorse 0:39935bb3c1a1 10 Mahony filter algorithms. Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1.
onehorse 0:39935bb3c1a1 11
onehorse 0:39935bb3c1a1 12 SDA and SCL should have external pull-up resistors (to 3.3V).
onehorse 0:39935bb3c1a1 13 10k resistors are on the EMSENSR-9250 breakout board.
onehorse 0:39935bb3c1a1 14
onehorse 0:39935bb3c1a1 15 Hardware setup:
onehorse 0:39935bb3c1a1 16 MPU9150 Breakout --------- Arduino
onehorse 0:39935bb3c1a1 17 VDD ---------------------- 3.3V
onehorse 0:39935bb3c1a1 18 VDDI --------------------- 3.3V
onehorse 0:39935bb3c1a1 19 SDA ----------------------- A4
onehorse 0:39935bb3c1a1 20 SCL ----------------------- A5
onehorse 0:39935bb3c1a1 21 GND ---------------------- GND
onehorse 0:39935bb3c1a1 22
onehorse 0:39935bb3c1a1 23 Note: The MPU9150 is an I2C sensor and uses the Arduino Wire library.
onehorse 0:39935bb3c1a1 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:39935bb3c1a1 25 We have disabled the internal pull-ups used by the Wire library in the Wire.h/twi.c utility file.
onehorse 0:39935bb3c1a1 26 We are also using the 400 kHz fast I2C mode by setting the TWI_FREQ to 400000L /twi.h utility file.
onehorse 0:39935bb3c1a1 27 */
onehorse 0:39935bb3c1a1 28
onehorse 0:39935bb3c1a1 29 //#include "ST_F401_84MHZ.h"
onehorse 0:39935bb3c1a1 30 //F401_init84 myinit(0);
onehorse 0:39935bb3c1a1 31 #include "mbed.h"
onehorse 0:39935bb3c1a1 32 #include "MPU9150.h"
onehorse 0:39935bb3c1a1 33 #include "N5110.h"
onehorse 0:39935bb3c1a1 34
onehorse 0:39935bb3c1a1 35 // Using NOKIA 5110 monochrome 84 x 48 pixel display
onehorse 0:39935bb3c1a1 36 // pin 9 - Serial clock out (SCLK)
onehorse 0:39935bb3c1a1 37 // pin 8 - Serial data out (DIN)
onehorse 0:39935bb3c1a1 38 // pin 7 - Data/Command select (D/C)
onehorse 0:39935bb3c1a1 39 // pin 5 - LCD chip select (CS)
onehorse 0:39935bb3c1a1 40 // pin 6 - LCD reset (RST)
onehorse 0:39935bb3c1a1 41 //Adafruit_PCD8544 display = Adafruit_PCD8544(9, 8, 7, 5, 6);
onehorse 0:39935bb3c1a1 42
onehorse 0:39935bb3c1a1 43 float sum = 0;
onehorse 0:39935bb3c1a1 44 uint32_t sumCount = 0, mcount = 0;
onehorse 0:39935bb3c1a1 45 char buffer[14];
onehorse 0:39935bb3c1a1 46
onehorse 0:39935bb3c1a1 47 MPU9150 MPU9150;
onehorse 0:39935bb3c1a1 48
onehorse 0:39935bb3c1a1 49 Timer t;
onehorse 0:39935bb3c1a1 50
onehorse 0:39935bb3c1a1 51 Serial pc(USBTX, USBRX); // tx, rx
onehorse 0:39935bb3c1a1 52
onehorse 0:39935bb3c1a1 53 // VCC, SCE, RST, D/C, MOSI,S CLK, LED
onehorse 0:39935bb3c1a1 54 N5110 lcd(PA_8, PB_10, PA_9, PA_6, PA_7, PA_5, PC_7);
onehorse 0:39935bb3c1a1 55
onehorse 0:39935bb3c1a1 56
onehorse 0:39935bb3c1a1 57
onehorse 0:39935bb3c1a1 58 int main()
onehorse 0:39935bb3c1a1 59 {
onehorse 0:39935bb3c1a1 60 pc.baud(9600);
onehorse 0:39935bb3c1a1 61
onehorse 0:39935bb3c1a1 62 //Set up I2C
onehorse 0:39935bb3c1a1 63 i2c.frequency(400000); // use fast (400 kHz) I2C
onehorse 0:39935bb3c1a1 64
onehorse 0:39935bb3c1a1 65 pc.printf("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock);
onehorse 0:39935bb3c1a1 66
onehorse 0:39935bb3c1a1 67 t.start();
onehorse 0:39935bb3c1a1 68
onehorse 0:39935bb3c1a1 69 lcd.init();
onehorse 0:39935bb3c1a1 70 // lcd.setBrightness(0.05);
onehorse 0:39935bb3c1a1 71
onehorse 0:39935bb3c1a1 72
onehorse 0:39935bb3c1a1 73 // Read the WHO_AM_I register, this is a good test of communication
onehorse 0:39935bb3c1a1 74 uint8_t whoami = MPU9150.readByte(MPU9150_ADDRESS, WHO_AM_I_MPU9150); // Read WHO_AM_I register for MPU-9250
onehorse 0:39935bb3c1a1 75 pc.printf("I AM 0x%x\n\r", whoami); pc.printf("I SHOULD BE 0x68\n\r");
onehorse 0:39935bb3c1a1 76
onehorse 0:39935bb3c1a1 77 if (whoami == 0x68) // WHO_AM_I should be 0x68
onehorse 0:39935bb3c1a1 78 {
onehorse 0:39935bb3c1a1 79 pc.printf("MPU9150 WHO_AM_I is 0x%x\n\r", whoami);
onehorse 0:39935bb3c1a1 80 pc.printf("MPU9150 is online...\n\r");
onehorse 0:39935bb3c1a1 81 lcd.clear();
onehorse 0:39935bb3c1a1 82 lcd.printString("MPU9150 is", 0, 0);
onehorse 0:39935bb3c1a1 83 sprintf(buffer, "0x%x", whoami);
onehorse 0:39935bb3c1a1 84 lcd.printString(buffer, 0, 1);
onehorse 0:39935bb3c1a1 85 lcd.printString("shoud be 0x68", 0, 2);
onehorse 0:39935bb3c1a1 86 wait(1);
onehorse 0:39935bb3c1a1 87
onehorse 0:39935bb3c1a1 88 MPU9150.MPU9150SelfTest(SelfTest);
onehorse 0:39935bb3c1a1 89 pc.printf("x-axis self test: acceleration trim within %f % of factory value\n\r", SelfTest[0]);
onehorse 0:39935bb3c1a1 90 pc.printf("y-axis self test: acceleration trim within %f % of factory value\n\r", SelfTest[1]);
onehorse 0:39935bb3c1a1 91 pc.printf("z-axis self test: acceleration trim within %f % of factory value\n\r", SelfTest[2]);
onehorse 0:39935bb3c1a1 92 pc.printf("x-axis self test: gyration trim within %f % of factory value\n\r", SelfTest[3]);
onehorse 0:39935bb3c1a1 93 pc.printf("y-axis self test: gyration trim within %f % of factory value\n\r", SelfTest[4]);
onehorse 0:39935bb3c1a1 94 pc.printf("z-axis self test: gyration trim within %f % of factory value\n\r", SelfTest[5]);
onehorse 0:39935bb3c1a1 95 wait(1);
onehorse 0:39935bb3c1a1 96 MPU9150.resetMPU9150(); // Reset registers to default in preparation for device calibration
onehorse 0:39935bb3c1a1 97 MPU9150.calibrateMPU9150(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers
onehorse 0:39935bb3c1a1 98 pc.printf("x gyro bias = %f\n\r", gyroBias[0]);
onehorse 0:39935bb3c1a1 99 pc.printf("y gyro bias = %f\n\r", gyroBias[1]);
onehorse 0:39935bb3c1a1 100 pc.printf("z gyro bias = %f\n\r", gyroBias[2]);
onehorse 0:39935bb3c1a1 101 pc.printf("x accel bias = %f\n\r", accelBias[0]);
onehorse 0:39935bb3c1a1 102 pc.printf("y accel bias = %f\n\r", accelBias[1]);
onehorse 0:39935bb3c1a1 103 pc.printf("z accel bias = %f\n\r", accelBias[2]);
onehorse 0:39935bb3c1a1 104 wait(1);
onehorse 0:39935bb3c1a1 105 MPU9150.initMPU9150();
onehorse 0:39935bb3c1a1 106 pc.printf("MPU9150 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature
onehorse 0:39935bb3c1a1 107 MPU9150.initAK8975A(magCalibration);
onehorse 0:39935bb3c1a1 108 pc.printf("AK8975 initialized for active data mode....\n\r"); // Initialize device for active mode read of magnetometer
onehorse 0:39935bb3c1a1 109 }
onehorse 0:39935bb3c1a1 110 else
onehorse 0:39935bb3c1a1 111 {
onehorse 0:39935bb3c1a1 112 pc.printf("Could not connect to MPU9150: \n\r");
onehorse 0:39935bb3c1a1 113 pc.printf("%#x \n", whoami);
onehorse 0:39935bb3c1a1 114
onehorse 0:39935bb3c1a1 115 lcd.clear();
onehorse 0:39935bb3c1a1 116 lcd.printString("MPU9150", 0, 0);
onehorse 0:39935bb3c1a1 117 lcd.printString("no connection", 0, 1);
onehorse 0:39935bb3c1a1 118 sprintf(buffer, "WHO_AM_I 0x%x", whoami);
onehorse 0:39935bb3c1a1 119 lcd.printString(buffer, 0, 2);
onehorse 0:39935bb3c1a1 120
onehorse 0:39935bb3c1a1 121 while(1) ; // Loop forever if communication doesn't happen
onehorse 0:39935bb3c1a1 122 }
onehorse 0:39935bb3c1a1 123
onehorse 0:39935bb3c1a1 124 uint8_t MagRate = 10; // set magnetometer read rate in Hz; 10 to 100 (max) Hz are reasonable values
onehorse 0:39935bb3c1a1 125 MPU9150.getAres(); // Get accelerometer sensitivity
onehorse 0:39935bb3c1a1 126 MPU9150.getGres(); // Get gyro sensitivity
onehorse 0:39935bb3c1a1 127 mRes = 10.*1229./4096.; // Conversion from 1229 microTesla full scale (4096) to 12.29 Gauss full scale
onehorse 0:39935bb3c1a1 128 // So far, magnetometer bias is calculated and subtracted here manually, should construct an algorithm to do it automatically
onehorse 0:39935bb3c1a1 129 // like the gyro and accelerometer biases
onehorse 0:39935bb3c1a1 130 magbias[0] = -5.; // User environmental x-axis correction in milliGauss
onehorse 0:39935bb3c1a1 131 magbias[1] = -95.; // User environmental y-axis correction in milliGauss
onehorse 0:39935bb3c1a1 132 magbias[2] = -260.; // User environmental z-axis correction in milliGauss
onehorse 0:39935bb3c1a1 133
onehorse 0:39935bb3c1a1 134
onehorse 0:39935bb3c1a1 135 while(1) {
onehorse 0:39935bb3c1a1 136
onehorse 0:39935bb3c1a1 137 // If intPin goes high, all data registers have new data
onehorse 0:39935bb3c1a1 138 if(MPU9150.readByte(MPU9150_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt
onehorse 0:39935bb3c1a1 139
onehorse 0:39935bb3c1a1 140 MPU9150.readAccelData(accelCount); // Read the x/y/z adc values
onehorse 0:39935bb3c1a1 141 // Now we'll calculate the accleration value into actual g's
onehorse 0:39935bb3c1a1 142 ax = (float)accelCount[0]*aRes; // - accelBias[0]; // get actual g value, this depends on scale being set
onehorse 0:39935bb3c1a1 143 ay = (float)accelCount[1]*aRes; // - accelBias[1];
onehorse 0:39935bb3c1a1 144 az = (float)accelCount[2]*aRes; // - accelBias[2];
onehorse 0:39935bb3c1a1 145
onehorse 0:39935bb3c1a1 146 MPU9150.readGyroData(gyroCount); // Read the x/y/z adc values
onehorse 0:39935bb3c1a1 147 // Calculate the gyro value into actual degrees per second
onehorse 0:39935bb3c1a1 148 gx = (float)gyroCount[0]*gRes; // - gyroBias[0]; // get actual gyro value, this depends on scale being set
onehorse 0:39935bb3c1a1 149 gy = (float)gyroCount[1]*gRes; // - gyroBias[1];
onehorse 0:39935bb3c1a1 150 gz = (float)gyroCount[2]*gRes; // - gyroBias[2];
onehorse 0:39935bb3c1a1 151
onehorse 0:39935bb3c1a1 152 mcount++;
onehorse 0:39935bb3c1a1 153 if (mcount > 200/MagRate) { // this is a poor man's way of setting the magnetometer read rate (see below)
onehorse 0:39935bb3c1a1 154 MPU9150.readMagData(magCount); // Read the x/y/z adc values
onehorse 0:39935bb3c1a1 155 // Calculate the magnetometer values in milliGauss
onehorse 0:39935bb3c1a1 156 // Include factory calibration per data sheet and user environmental corrections
onehorse 0:39935bb3c1a1 157 mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0]; // get actual magnetometer value, this depends on scale being set
onehorse 0:39935bb3c1a1 158 my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1];
onehorse 0:39935bb3c1a1 159 mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2];
onehorse 0:39935bb3c1a1 160 mcount = 0;
onehorse 0:39935bb3c1a1 161 }
onehorse 0:39935bb3c1a1 162 }
onehorse 0:39935bb3c1a1 163
onehorse 0:39935bb3c1a1 164 Now = t.read_us();
onehorse 0:39935bb3c1a1 165 deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update
onehorse 0:39935bb3c1a1 166 lastUpdate = Now;
onehorse 0:39935bb3c1a1 167
onehorse 0:39935bb3c1a1 168 sum += deltat;
onehorse 0:39935bb3c1a1 169 sumCount++;
onehorse 0:39935bb3c1a1 170
onehorse 0:39935bb3c1a1 171 // if(lastUpdate - firstUpdate > 10000000.0f) {
onehorse 0:39935bb3c1a1 172 // beta = 0.04; // decrease filter gain after stabilized
onehorse 0:39935bb3c1a1 173 // zeta = 0.015; // increasey bias drift gain after stabilized
onehorse 0:39935bb3c1a1 174 // }
onehorse 0:39935bb3c1a1 175
onehorse 0:39935bb3c1a1 176 // Pass gyro rate as rad/s
onehorse 0:39935bb3c1a1 177 // MPU9150.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
onehorse 0:39935bb3c1a1 178 MPU9150.MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
onehorse 0:39935bb3c1a1 179
onehorse 0:39935bb3c1a1 180 // Serial print and/or display at 0.5 s rate independent of data rates
onehorse 0:39935bb3c1a1 181 delt_t = t.read_ms() - count;
onehorse 0:39935bb3c1a1 182 if (delt_t > 500) { // update LCD once per half-second independent of read rate
onehorse 0:39935bb3c1a1 183
onehorse 0:39935bb3c1a1 184 pc.printf("ax = %f", 1000*ax);
onehorse 0:39935bb3c1a1 185 pc.printf(" ay = %f", 1000*ay);
onehorse 0:39935bb3c1a1 186 pc.printf(" az = %f mg\n\r", 1000*az);
onehorse 0:39935bb3c1a1 187
onehorse 0:39935bb3c1a1 188 pc.printf("gx = %f", gx);
onehorse 0:39935bb3c1a1 189 pc.printf(" gy = %f", gy);
onehorse 0:39935bb3c1a1 190 pc.printf(" gz = %f deg/s\n\r", gz);
onehorse 0:39935bb3c1a1 191
onehorse 0:39935bb3c1a1 192 pc.printf("gx = %f", mx);
onehorse 0:39935bb3c1a1 193 pc.printf(" gy = %f", my);
onehorse 0:39935bb3c1a1 194 pc.printf(" gz = %f mG\n\r", mz);
onehorse 0:39935bb3c1a1 195
onehorse 0:39935bb3c1a1 196 tempCount = MPU9150.readTempData(); // Read the adc values
onehorse 0:39935bb3c1a1 197 temperature = ((float) tempCount) / 340.0f + 36.53f; // Temperature in degrees Centigrade
onehorse 0:39935bb3c1a1 198 pc.printf(" temperature = %f C\n\r", temperature);
onehorse 0:39935bb3c1a1 199
onehorse 0:39935bb3c1a1 200 pc.printf("q0 = %f\n\r", q[0]);
onehorse 0:39935bb3c1a1 201 pc.printf("q1 = %f\n\r", q[1]);
onehorse 0:39935bb3c1a1 202 pc.printf("q2 = %f\n\r", q[2]);
onehorse 0:39935bb3c1a1 203 pc.printf("q3 = %f\n\r", q[3]);
onehorse 0:39935bb3c1a1 204
onehorse 0:39935bb3c1a1 205 /* lcd.clear();
onehorse 0:39935bb3c1a1 206 lcd.printString("MPU9150", 0, 0);
onehorse 0:39935bb3c1a1 207 lcd.printString("x y z", 0, 1);
onehorse 0:39935bb3c1a1 208 sprintf(buffer, "%d %d %d mg", (int)(1000.0f*ax), (int)(1000.0f*ay), (int)(1000.0f*az));
onehorse 0:39935bb3c1a1 209 lcd.printString(buffer, 0, 2);
onehorse 0:39935bb3c1a1 210 sprintf(buffer, "%d %d %d deg/s", (int)gx, (int)gy, (int)gz);
onehorse 0:39935bb3c1a1 211 lcd.printString(buffer, 0, 3);
onehorse 0:39935bb3c1a1 212 sprintf(buffer, "%d %d %d mG", (int)mx, (int)my, (int)mz);
onehorse 0:39935bb3c1a1 213 lcd.printString(buffer, 0, 4);
onehorse 0:39935bb3c1a1 214 */
onehorse 0:39935bb3c1a1 215 // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation.
onehorse 0:39935bb3c1a1 216 // In this coordinate system, the positive z-axis is down toward Earth.
onehorse 0:39935bb3c1a1 217 // 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:39935bb3c1a1 218 // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative.
onehorse 0:39935bb3c1a1 219 // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll.
onehorse 0:39935bb3c1a1 220 // These arise from the definition of the homogeneous rotation matrix constructed from quaternions.
onehorse 0:39935bb3c1a1 221 // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be
onehorse 0:39935bb3c1a1 222 // applied in the correct order which for this configuration is yaw, pitch, and then roll.
onehorse 0:39935bb3c1a1 223 // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links.
onehorse 0:39935bb3c1a1 224 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:39935bb3c1a1 225 pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
onehorse 0:39935bb3c1a1 226 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:39935bb3c1a1 227 pitch *= 180.0f / PI;
onehorse 0:39935bb3c1a1 228 yaw *= 180.0f / PI;
onehorse 0:39935bb3c1a1 229 yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04
onehorse 0:39935bb3c1a1 230 roll *= 180.0f / PI;
onehorse 0:39935bb3c1a1 231
onehorse 0:39935bb3c1a1 232 pc.printf("Yaw, Pitch, Roll: %f %f %f\n\r", yaw, pitch, roll);
onehorse 0:39935bb3c1a1 233 pc.printf("average rate = %f\n\r", (float) sumCount/sum);
onehorse 0:39935bb3c1a1 234 // sprintf(buffer, "YPR: %f %f %f", yaw, pitch, roll);
onehorse 0:39935bb3c1a1 235 // lcd.printString(buffer, 0, 4);
onehorse 0:39935bb3c1a1 236 // sprintf(buffer, "rate = %f", (float) sumCount/sum);
onehorse 0:39935bb3c1a1 237 // lcd.printString(buffer, 0, 5);
onehorse 0:39935bb3c1a1 238
onehorse 0:39935bb3c1a1 239 myled= !myled;
onehorse 0:39935bb3c1a1 240 count = t.read_ms();
onehorse 0:39935bb3c1a1 241
onehorse 0:39935bb3c1a1 242 if(count > 1<<21) {
onehorse 0:39935bb3c1a1 243 t.start(); // start the timer over again if ~30 minutes has passed
onehorse 0:39935bb3c1a1 244 count = 0;
onehorse 0:39935bb3c1a1 245 deltat= 0;
onehorse 0:39935bb3c1a1 246 lastUpdate = t.read_us();
onehorse 0:39935bb3c1a1 247 }
onehorse 0:39935bb3c1a1 248 sum = 0;
onehorse 0:39935bb3c1a1 249 sumCount = 0;
onehorse 0:39935bb3c1a1 250 }
onehorse 0:39935bb3c1a1 251 }
onehorse 0:39935bb3c1a1 252
onehorse 0:39935bb3c1a1 253 }