Filter for 9250

Dependencies:   mbed

Fork of MPU9250 by Ilia Manenok

Committer:
farhanalam
Date:
Sat Jun 10 23:47:23 2017 +0000
Revision:
1:3cf2930938a8
Parent:
0:ccea261dce7a
Child:
2:6b427a493d9b
basic mpu9250  working code

Who changed what in which revision?

UserRevisionLine numberNew contents of line
imanyonok 0:ccea261dce7a 1 /* MPU9250 Basic Example Code
imanyonok 0:ccea261dce7a 2 by: Kris Winer
imanyonok 0:ccea261dce7a 3 date: April 1, 2014
imanyonok 0:ccea261dce7a 4 license: Beerware - Use this code however you'd like. If you
imanyonok 0:ccea261dce7a 5 find it useful you can buy me a beer some time.
imanyonok 0:ccea261dce7a 6
imanyonok 0:ccea261dce7a 7 Demonstrate basic MPU-9250 functionality including parameterizing the register addresses, initializing the sensor,
imanyonok 0:ccea261dce7a 8 getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to
imanyonok 0:ccea261dce7a 9 allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and
imanyonok 0:ccea261dce7a 10 Mahony filter algorithms. Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1.
imanyonok 0:ccea261dce7a 11
imanyonok 0:ccea261dce7a 12 SDA and SCL should have external pull-up resistors (to 3.3V).
imanyonok 0:ccea261dce7a 13 10k resistors are on the EMSENSR-9250 breakout board.
imanyonok 0:ccea261dce7a 14
imanyonok 0:ccea261dce7a 15 Hardware setup:
imanyonok 0:ccea261dce7a 16 MPU9250 Breakout --------- Arduino
imanyonok 0:ccea261dce7a 17 VDD ---------------------- 3.3V
imanyonok 0:ccea261dce7a 18 VDDI --------------------- 3.3V
imanyonok 0:ccea261dce7a 19 SDA ----------------------- A4
imanyonok 0:ccea261dce7a 20 SCL ----------------------- A5
imanyonok 0:ccea261dce7a 21 GND ---------------------- GND
imanyonok 0:ccea261dce7a 22
imanyonok 0:ccea261dce7a 23 Note: The MPU9250 is an I2C sensor and uses the Arduino Wire library.
imanyonok 0:ccea261dce7a 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.
imanyonok 0:ccea261dce7a 25 We have disabled the internal pull-ups used by the Wire library in the Wire.h/twi.c utility file.
imanyonok 0:ccea261dce7a 26 We are also using the 400 kHz fast I2C mode by setting the TWI_FREQ to 400000L /twi.h utility file.
imanyonok 0:ccea261dce7a 27 */
farhanalam 1:3cf2930938a8 28 //yellow on PB9
farhanalam 1:3cf2930938a8 29 //Green on PB8
farhanalam 1:3cf2930938a8 30 //brown 3,3V
farhanalam 1:3cf2930938a8 31 //black GND
imanyonok 0:ccea261dce7a 32 #include "mbed.h"
imanyonok 0:ccea261dce7a 33 #include "MPU9250.h"
imanyonok 0:ccea261dce7a 34
imanyonok 0:ccea261dce7a 35
imanyonok 0:ccea261dce7a 36 float sum = 0;
imanyonok 0:ccea261dce7a 37 uint32_t sumCount = 0;
imanyonok 0:ccea261dce7a 38
imanyonok 0:ccea261dce7a 39 MPU9250 mpu9250;
imanyonok 0:ccea261dce7a 40
imanyonok 0:ccea261dce7a 41 Timer t;
imanyonok 0:ccea261dce7a 42
imanyonok 0:ccea261dce7a 43 Serial pc(USBTX, USBRX); // tx, rx
imanyonok 0:ccea261dce7a 44
imanyonok 0:ccea261dce7a 45
imanyonok 0:ccea261dce7a 46 int main()
imanyonok 0:ccea261dce7a 47 {
imanyonok 0:ccea261dce7a 48 pc.baud(9600);
farhanalam 1:3cf2930938a8 49
farhanalam 1:3cf2930938a8 50 // while(1)
farhanalam 1:3cf2930938a8 51 //{
farhanalam 1:3cf2930938a8 52 wait(.5);
farhanalam 1:3cf2930938a8 53
farhanalam 1:3cf2930938a8 54 //}
imanyonok 0:ccea261dce7a 55 //Set up I2C
farhanalam 1:3cf2930938a8 56 i2c.frequency(1000000); // use fast (400 kHz) I2C
imanyonok 0:ccea261dce7a 57
imanyonok 0:ccea261dce7a 58 pc.printf("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock);
imanyonok 0:ccea261dce7a 59
imanyonok 0:ccea261dce7a 60 t.start();
imanyonok 0:ccea261dce7a 61
imanyonok 0:ccea261dce7a 62
imanyonok 0:ccea261dce7a 63
imanyonok 0:ccea261dce7a 64 // Read the WHO_AM_I register, this is a good test of communication
imanyonok 0:ccea261dce7a 65 uint8_t whoami = mpu9250.readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250); // Read WHO_AM_I register for MPU-9250
imanyonok 0:ccea261dce7a 66 pc.printf("I AM 0x%x\n\r", whoami); pc.printf("I SHOULD BE 0x71\n\r");
imanyonok 0:ccea261dce7a 67
imanyonok 0:ccea261dce7a 68 if (whoami == 0x71) // WHO_AM_I should always be 0x68
imanyonok 0:ccea261dce7a 69 {
imanyonok 0:ccea261dce7a 70 pc.printf("MPU9250 is online...\n\r");
imanyonok 0:ccea261dce7a 71 wait(1);
imanyonok 0:ccea261dce7a 72
imanyonok 0:ccea261dce7a 73
imanyonok 0:ccea261dce7a 74 mpu9250.resetMPU9250(); // Reset registers to default in preparation for device calibration
imanyonok 0:ccea261dce7a 75 mpu9250.calibrateMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers
imanyonok 0:ccea261dce7a 76 //pc.printf("x gyro bias = %f\n\r", gyroBias[0]);
imanyonok 0:ccea261dce7a 77 //pc.printf("y gyro bias = %f\n\r", gyroBias[1]);
imanyonok 0:ccea261dce7a 78 //pc.printf("z gyro bias = %f\n\r", gyroBias[2]);
imanyonok 0:ccea261dce7a 79 //pc.printf("x accel bias = %f\n\r", accelBias[0]);
imanyonok 0:ccea261dce7a 80 //pc.printf("y accel bias = %f\n\r", accelBias[1]);
imanyonok 0:ccea261dce7a 81 //pc.printf("z accel bias = %f\n\r", accelBias[2]);
imanyonok 0:ccea261dce7a 82 wait(2);
imanyonok 0:ccea261dce7a 83 mpu9250.initMPU9250();
imanyonok 0:ccea261dce7a 84 pc.printf("MPU9250 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature
imanyonok 0:ccea261dce7a 85 mpu9250.initAK8963(magCalibration);
imanyonok 0:ccea261dce7a 86 pc.printf("AK8963 initialized for active data mode....\n\r"); // Initialize device for active mode read of magnetometer
imanyonok 0:ccea261dce7a 87 pc.printf("Accelerometer full-scale range = %f g\n\r", 2.0f*(float)(1<<Ascale));
imanyonok 0:ccea261dce7a 88 pc.printf("Gyroscope full-scale range = %f deg/s\n\r", 250.0f*(float)(1<<Gscale));
imanyonok 0:ccea261dce7a 89 if(Mscale == 0) pc.printf("Magnetometer resolution = 14 bits\n\r");
imanyonok 0:ccea261dce7a 90 if(Mscale == 1) pc.printf("Magnetometer resolution = 16 bits\n\r");
imanyonok 0:ccea261dce7a 91 if(Mmode == 2) pc.printf("Magnetometer ODR = 8 Hz\n\r");
imanyonok 0:ccea261dce7a 92 if(Mmode == 6) pc.printf("Magnetometer ODR = 100 Hz\n\r");
imanyonok 0:ccea261dce7a 93 wait(2);
imanyonok 0:ccea261dce7a 94 }
imanyonok 0:ccea261dce7a 95 else
imanyonok 0:ccea261dce7a 96 {
imanyonok 0:ccea261dce7a 97 pc.printf("Could not connect to MPU9250: \n\r");
imanyonok 0:ccea261dce7a 98 pc.printf("%#x \n", whoami);
imanyonok 0:ccea261dce7a 99
imanyonok 0:ccea261dce7a 100
imanyonok 0:ccea261dce7a 101
imanyonok 0:ccea261dce7a 102 while(1) ; // Loop forever if communication doesn't happen
imanyonok 0:ccea261dce7a 103 }
imanyonok 0:ccea261dce7a 104
imanyonok 0:ccea261dce7a 105 mpu9250.getAres(); // Get accelerometer sensitivity
imanyonok 0:ccea261dce7a 106 mpu9250.getGres(); // Get gyro sensitivity
imanyonok 0:ccea261dce7a 107 mpu9250.getMres(); // Get magnetometer sensitivity
imanyonok 0:ccea261dce7a 108 //pc.printf("Accelerometer sensitivity is %f LSB/g \n\r", 1.0f/aRes);
imanyonok 0:ccea261dce7a 109 //pc.printf("Gyroscope sensitivity is %f LSB/deg/s \n\r", 1.0f/gRes);
imanyonok 0:ccea261dce7a 110 //pc.printf("Magnetometer sensitivity is %f LSB/G \n\r", 1.0f/mRes);
imanyonok 0:ccea261dce7a 111 magbias[0] = +470.; // User environmental x-axis correction in milliGauss, should be automatically calculated
imanyonok 0:ccea261dce7a 112 magbias[1] = +120.; // User environmental x-axis correction in milliGauss
imanyonok 0:ccea261dce7a 113 magbias[2] = +125.; // User environmental x-axis correction in milliGauss
imanyonok 0:ccea261dce7a 114
imanyonok 0:ccea261dce7a 115 while(1) {
imanyonok 0:ccea261dce7a 116
imanyonok 0:ccea261dce7a 117 // If intPin goes high, all data registers have new data
imanyonok 0:ccea261dce7a 118 if(mpu9250.readByte(MPU9250_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt
imanyonok 0:ccea261dce7a 119
imanyonok 0:ccea261dce7a 120 mpu9250.readAccelData(accelCount); // Read the x/y/z adc values
imanyonok 0:ccea261dce7a 121 // Now we'll calculate the accleration value into actual g's
imanyonok 0:ccea261dce7a 122 ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set
imanyonok 0:ccea261dce7a 123 ay = (float)accelCount[1]*aRes - accelBias[1];
imanyonok 0:ccea261dce7a 124 az = (float)accelCount[2]*aRes - accelBias[2];
imanyonok 0:ccea261dce7a 125
imanyonok 0:ccea261dce7a 126 mpu9250.readGyroData(gyroCount); // Read the x/y/z adc values
imanyonok 0:ccea261dce7a 127 // Calculate the gyro value into actual degrees per second
imanyonok 0:ccea261dce7a 128 gx = (float)gyroCount[0]*gRes - gyroBias[0]; // get actual gyro value, this depends on scale being set
imanyonok 0:ccea261dce7a 129 gy = (float)gyroCount[1]*gRes - gyroBias[1];
imanyonok 0:ccea261dce7a 130 gz = (float)gyroCount[2]*gRes - gyroBias[2];
imanyonok 0:ccea261dce7a 131
imanyonok 0:ccea261dce7a 132 mpu9250.readMagData(magCount); // Read the x/y/z adc values
imanyonok 0:ccea261dce7a 133 // Calculate the magnetometer values in milliGauss
imanyonok 0:ccea261dce7a 134 // Include factory calibration per data sheet and user environmental corrections
imanyonok 0:ccea261dce7a 135 mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0]; // get actual magnetometer value, this depends on scale being set
imanyonok 0:ccea261dce7a 136 my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1];
imanyonok 0:ccea261dce7a 137 mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2];
imanyonok 0:ccea261dce7a 138 }
imanyonok 0:ccea261dce7a 139
imanyonok 0:ccea261dce7a 140 Now = t.read_us();
imanyonok 0:ccea261dce7a 141 deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update
imanyonok 0:ccea261dce7a 142 lastUpdate = Now;
imanyonok 0:ccea261dce7a 143
imanyonok 0:ccea261dce7a 144 sum += deltat;
imanyonok 0:ccea261dce7a 145 sumCount++;
imanyonok 0:ccea261dce7a 146
imanyonok 0:ccea261dce7a 147 // if(lastUpdate - firstUpdate > 10000000.0f) {
imanyonok 0:ccea261dce7a 148 // beta = 0.04; // decrease filter gain after stabilized
imanyonok 0:ccea261dce7a 149 // zeta = 0.015; // increasey bias drift gain after stabilized
imanyonok 0:ccea261dce7a 150 // }
imanyonok 0:ccea261dce7a 151
imanyonok 0:ccea261dce7a 152 // Pass gyro rate as rad/s
imanyonok 0:ccea261dce7a 153 mpu9250.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
imanyonok 0:ccea261dce7a 154 mpu9250.MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
imanyonok 0:ccea261dce7a 155
imanyonok 0:ccea261dce7a 156 // Serial print and/or display at 0.5 s rate independent of data rates
imanyonok 0:ccea261dce7a 157 delt_t = t.read_ms() - count;
farhanalam 1:3cf2930938a8 158 if (delt_t > 1000) { // update LCD once per half-second independent of read rate
imanyonok 0:ccea261dce7a 159
imanyonok 0:ccea261dce7a 160 pc.printf("ax = %f", 1000*ax);
imanyonok 0:ccea261dce7a 161 pc.printf(" ay = %f", 1000*ay);
imanyonok 0:ccea261dce7a 162 pc.printf(" az = %f mg\n\r", 1000*az);
imanyonok 0:ccea261dce7a 163
imanyonok 0:ccea261dce7a 164 //pc.printf("gx = %f", gx);
imanyonok 0:ccea261dce7a 165 //pc.printf(" gy = %f", gy);
imanyonok 0:ccea261dce7a 166 //pc.printf(" gz = %f deg/s\n\r", gz);
imanyonok 0:ccea261dce7a 167
imanyonok 0:ccea261dce7a 168 //pc.printf("gx = %f", mx);
imanyonok 0:ccea261dce7a 169 //pc.printf(" gy = %f", my);
imanyonok 0:ccea261dce7a 170 //pc.printf(" gz = %f mG\n\r", mz);
imanyonok 0:ccea261dce7a 171
imanyonok 0:ccea261dce7a 172 tempCount = mpu9250.readTempData(); // Read the adc values
imanyonok 0:ccea261dce7a 173 temperature = ((float) tempCount) / 333.87f + 21.0f; // Temperature in degrees Centigrade
imanyonok 0:ccea261dce7a 174 //pc.printf(" temperature = %f C\n\r", temperature);
imanyonok 0:ccea261dce7a 175
imanyonok 0:ccea261dce7a 176 //pc.printf("q0 = %f\n\r", q[0]);
imanyonok 0:ccea261dce7a 177 //pc.printf("q1 = %f\n\r", q[1]);
imanyonok 0:ccea261dce7a 178 //pc.printf("q2 = %f\n\r", q[2]);
imanyonok 0:ccea261dce7a 179 //pc.printf("q3 = %f\n\r", q[3]);
imanyonok 0:ccea261dce7a 180
imanyonok 0:ccea261dce7a 181
imanyonok 0:ccea261dce7a 182 // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation.
imanyonok 0:ccea261dce7a 183 // In this coordinate system, the positive z-axis is down toward Earth.
imanyonok 0:ccea261dce7a 184 // 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.
imanyonok 0:ccea261dce7a 185 // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative.
imanyonok 0:ccea261dce7a 186 // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll.
imanyonok 0:ccea261dce7a 187 // These arise from the definition of the homogeneous rotation matrix constructed from quaternions.
imanyonok 0:ccea261dce7a 188 // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be
imanyonok 0:ccea261dce7a 189 // applied in the correct order which for this configuration is yaw, pitch, and then roll.
imanyonok 0:ccea261dce7a 190 // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links.
imanyonok 0:ccea261dce7a 191 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]);
imanyonok 0:ccea261dce7a 192 pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
imanyonok 0:ccea261dce7a 193 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]);
imanyonok 0:ccea261dce7a 194 pitch *= 180.0f / PI;
imanyonok 0:ccea261dce7a 195 yaw *= 180.0f / PI;
imanyonok 0:ccea261dce7a 196 yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04
imanyonok 0:ccea261dce7a 197 roll *= 180.0f / PI;
imanyonok 0:ccea261dce7a 198
imanyonok 0:ccea261dce7a 199 pc.printf("Yaw, Pitch, Roll: %f %f %f \n\r", yaw, pitch, roll);
imanyonok 0:ccea261dce7a 200 //pc.printf("average rate = %f\n\r", (float) sumCount/sum);
imanyonok 0:ccea261dce7a 201
imanyonok 0:ccea261dce7a 202 myled= !myled;
imanyonok 0:ccea261dce7a 203 count = t.read_ms();
imanyonok 0:ccea261dce7a 204 sum = 0;
imanyonok 0:ccea261dce7a 205 sumCount = 0;
imanyonok 0:ccea261dce7a 206 }
imanyonok 0:ccea261dce7a 207 }
imanyonok 0:ccea261dce7a 208
imanyonok 0:ccea261dce7a 209 }