IMU for turtle robot project

Dependencies:   mbed

Committer:
worasuchad
Date:
Sun Jan 28 09:02:04 2018 +0000
Revision:
4:5002036c82df
Parent:
3:0d58dbc24178
edit print

Who changed what in which revision?

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