Stabilizer

Dependencies:   BEAR_Protocol mbed Stabilizer iSerial

Fork of MPU9250AHRS by BE@R lab

Committer:
soulx
Date:
Fri Dec 18 12:59:56 2015 +0000
Revision:
3:3e04c1c03cab
Parent:
1:71c319f03fda
Child:
4:1e5db958fd1b
test new caribation

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
soulx 3:3e04c1c03cab 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.
soulx 3:3e04c1c03cab 6
soulx 3:3e04c1c03cab 7 Demonstrate basic MPU-9250 functionality including parameterizing the register addresses, initializing the sensor,
soulx 3:3e04c1c03cab 8 getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to
soulx 3:3e04c1c03cab 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.
soulx 3:3e04c1c03cab 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.
soulx 3:3e04c1c03cab 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
soulx 3:3e04c1c03cab 22
soulx 3:3e04c1c03cab 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 */
soulx 3:3e04c1c03cab 28
soulx 3:3e04c1c03cab 29 //#include "ST_F401_84MHZ.h"
onehorse 0:2e5e65a6fb30 30 //F401_init84 myinit(0);
onehorse 0:2e5e65a6fb30 31 #include "mbed.h"
onehorse 0:2e5e65a6fb30 32 #include "MPU9250.h"
soulx 3:3e04c1c03cab 33 //#include "N5110.h"
onehorse 0:2e5e65a6fb30 34
onehorse 0:2e5e65a6fb30 35 // Using NOKIA 5110 monochrome 84 x 48 pixel display
onehorse 0:2e5e65a6fb30 36 // pin 9 - Serial clock out (SCLK)
onehorse 0:2e5e65a6fb30 37 // pin 8 - Serial data out (DIN)
onehorse 0:2e5e65a6fb30 38 // pin 7 - Data/Command select (D/C)
onehorse 0:2e5e65a6fb30 39 // pin 5 - LCD chip select (CS)
onehorse 0:2e5e65a6fb30 40 // pin 6 - LCD reset (RST)
onehorse 0:2e5e65a6fb30 41 //Adafruit_PCD8544 display = Adafruit_PCD8544(9, 8, 7, 5, 6);
onehorse 0:2e5e65a6fb30 42
onehorse 0:2e5e65a6fb30 43 float sum = 0;
onehorse 0:2e5e65a6fb30 44 uint32_t sumCount = 0;
onehorse 0:2e5e65a6fb30 45 char buffer[14];
onehorse 0:2e5e65a6fb30 46
soulx 3:3e04c1c03cab 47 MPU9250 mpu9250;
soulx 3:3e04c1c03cab 48
soulx 3:3e04c1c03cab 49 Timer t;
onehorse 0:2e5e65a6fb30 50
soulx 3:3e04c1c03cab 51 Serial pc(USBTX, USBRX); // tx, rx
soulx 3:3e04c1c03cab 52
soulx 3:3e04c1c03cab 53 // VCC, SCE, RST, D/C, MOSI,S CLK, LED
soulx 3:3e04c1c03cab 54 //N5110 lcd(PA_8, PB_10, PA_9, PA_6, PA_7, PA_5, PC_7);
soulx 3:3e04c1c03cab 55 float xmax = -4914.0f;
soulx 3:3e04c1c03cab 56 float xmin = 4914.0f;
onehorse 0:2e5e65a6fb30 57
soulx 3:3e04c1c03cab 58 float ymax = -4914.0;
soulx 3:3e04c1c03cab 59 float ymin = 4914.0f;
soulx 3:3e04c1c03cab 60
soulx 3:3e04c1c03cab 61 float zmax = -4914.0;
soulx 3:3e04c1c03cab 62 float zmin = 4914.0f;
onehorse 0:2e5e65a6fb30 63
soulx 3:3e04c1c03cab 64 float Xsf,Ysf;
soulx 3:3e04c1c03cab 65 float Xoff,Yoff;
soulx 3:3e04c1c03cab 66
soulx 3:3e04c1c03cab 67
soulx 3:3e04c1c03cab 68 //InterruptIn event(PC_13);
soulx 3:3e04c1c03cab 69 DigitalIn enable(PC_13);
soulx 3:3e04c1c03cab 70
onehorse 0:2e5e65a6fb30 71 int main()
onehorse 0:2e5e65a6fb30 72 {
soulx 3:3e04c1c03cab 73
soulx 3:3e04c1c03cab 74 pc.baud(115200);
soulx 3:3e04c1c03cab 75
soulx 3:3e04c1c03cab 76 //Set up I2C
soulx 3:3e04c1c03cab 77 i2c.frequency(400000); // use fast (400 kHz) I2C
onehorse 0:2e5e65a6fb30 78
soulx 3:3e04c1c03cab 79 pc.printf("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock);
soulx 3:3e04c1c03cab 80
soulx 3:3e04c1c03cab 81 t.start();
soulx 3:3e04c1c03cab 82
soulx 3:3e04c1c03cab 83 //lcd.init();
onehorse 0:2e5e65a6fb30 84 // lcd.setBrightness(0.05);
soulx 3:3e04c1c03cab 85
soulx 3:3e04c1c03cab 86 //mpu9250.resetMPU9250();
soulx 3:3e04c1c03cab 87 // Read the WHO_AM_I register, this is a good test of communication
soulx 3:3e04c1c03cab 88 uint8_t whoami = mpu9250.readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250); // Read WHO_AM_I register for MPU-9250
soulx 3:3e04c1c03cab 89 pc.printf("I AM 0x%x\n\r", whoami);
soulx 3:3e04c1c03cab 90 pc.printf("I SHOULD BE 0x71\n\r");
soulx 3:3e04c1c03cab 91
soulx 3:3e04c1c03cab 92 if (whoami == 0x71) { // WHO_AM_I should always be 0x68
soulx 3:3e04c1c03cab 93 pc.printf("MPU9250 WHO_AM_I is 0x%x\n\r", whoami);
soulx 3:3e04c1c03cab 94 pc.printf("MPU9250 is online...\n\r");
soulx 3:3e04c1c03cab 95 // lcd.clear();
soulx 3:3e04c1c03cab 96 // lcd.printString("MPU9250 is", 0, 0);
soulx 3:3e04c1c03cab 97 sprintf(buffer, "0x%x", whoami);
soulx 3:3e04c1c03cab 98 // lcd.printString(buffer, 0, 1);
soulx 3:3e04c1c03cab 99 // lcd.printString("shoud be 0x71", 0, 2);
soulx 3:3e04c1c03cab 100 wait(1);
soulx 3:3e04c1c03cab 101
soulx 3:3e04c1c03cab 102 mpu9250.resetMPU9250(); // Reset registers to default in preparation for device calibration
soulx 3:3e04c1c03cab 103 mpu9250.MPU9250SelfTest(SelfTest); // Start by performing self test and reporting values
soulx 3:3e04c1c03cab 104 pc.printf("x-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[0]);
soulx 3:3e04c1c03cab 105 pc.printf("y-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[1]);
soulx 3:3e04c1c03cab 106 pc.printf("z-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[2]);
soulx 3:3e04c1c03cab 107 pc.printf("x-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[3]);
soulx 3:3e04c1c03cab 108 pc.printf("y-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[4]);
soulx 3:3e04c1c03cab 109 pc.printf("z-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[5]);
soulx 3:3e04c1c03cab 110 mpu9250.calibrateMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers
soulx 3:3e04c1c03cab 111 pc.printf("x gyro bias = %f\n\r", gyroBias[0]);
soulx 3:3e04c1c03cab 112 pc.printf("y gyro bias = %f\n\r", gyroBias[1]);
soulx 3:3e04c1c03cab 113 pc.printf("z gyro bias = %f\n\r", gyroBias[2]);
soulx 3:3e04c1c03cab 114 pc.printf("x accel bias = %f\n\r", accelBias[0]);
soulx 3:3e04c1c03cab 115 pc.printf("y accel bias = %f\n\r", accelBias[1]);
soulx 3:3e04c1c03cab 116 pc.printf("z accel bias = %f\n\r", accelBias[2]);
soulx 3:3e04c1c03cab 117 wait(2);
soulx 3:3e04c1c03cab 118 mpu9250.initMPU9250();
soulx 3:3e04c1c03cab 119 pc.printf("MPU9250 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature
soulx 3:3e04c1c03cab 120 mpu9250.initAK8963(magCalibration);
soulx 3:3e04c1c03cab 121 pc.printf("AK8963 initialized for active data mode....\n\r"); // Initialize device for active mode read of magnetometer
soulx 3:3e04c1c03cab 122
soulx 3:3e04c1c03cab 123 whoami = mpu9250.readByte(AK8963_ADDRESS, WHO_AM_I_AK8963); // Read WHO_AM_I register for MPU-9250
soulx 3:3e04c1c03cab 124 pc.printf("I AM 0x%x\n\r", whoami);
soulx 3:3e04c1c03cab 125 pc.printf("I SHOULD BE 0x48\n\r");
soulx 3:3e04c1c03cab 126 if(whoami != 0x48) {
soulx 3:3e04c1c03cab 127 while(1);
soulx 3:3e04c1c03cab 128 }
soulx 3:3e04c1c03cab 129 pc.printf("Accelerometer full-scale range = %f g\n\r", 2.0f*(float)(1<<Ascale));
soulx 3:3e04c1c03cab 130 pc.printf("Gyroscope full-scale range = %f deg/s\n\r", 250.0f*(float)(1<<Gscale));
soulx 3:3e04c1c03cab 131 if(Mscale == 0) pc.printf("Magnetometer resolution = 14 bits\n\r");
soulx 3:3e04c1c03cab 132 if(Mscale == 1) pc.printf("Magnetometer resolution = 16 bits\n\r");
soulx 3:3e04c1c03cab 133 if(Mmode == 2) pc.printf("Magnetometer ODR = 8 Hz\n\r");
soulx 3:3e04c1c03cab 134 if(Mmode == 6) pc.printf("Magnetometer ODR = 100 Hz\n\r");
soulx 3:3e04c1c03cab 135 wait(1);
soulx 3:3e04c1c03cab 136 } else {
soulx 3:3e04c1c03cab 137 pc.printf("Could not connect to MPU9250: \n\r");
soulx 3:3e04c1c03cab 138 pc.printf("%#x \n", whoami);
soulx 3:3e04c1c03cab 139
soulx 3:3e04c1c03cab 140 //lcd.clear();
soulx 3:3e04c1c03cab 141 //lcd.printString("MPU9250", 0, 0);
soulx 3:3e04c1c03cab 142 //lcd.printString("no connection", 0, 1);
soulx 3:3e04c1c03cab 143 sprintf(buffer, "WHO_AM_I 0x%x", whoami);
soulx 3:3e04c1c03cab 144 //lcd.printString(buffer, 0, 2);
soulx 3:3e04c1c03cab 145
soulx 3:3e04c1c03cab 146 while(1) ; // Loop forever if communication doesn't happen
onehorse 0:2e5e65a6fb30 147 }
onehorse 0:2e5e65a6fb30 148
onehorse 0:2e5e65a6fb30 149 mpu9250.getAres(); // Get accelerometer sensitivity
onehorse 0:2e5e65a6fb30 150 mpu9250.getGres(); // Get gyro sensitivity
onehorse 0:2e5e65a6fb30 151 mpu9250.getMres(); // Get magnetometer sensitivity
onehorse 0:2e5e65a6fb30 152 pc.printf("Accelerometer sensitivity is %f LSB/g \n\r", 1.0f/aRes);
onehorse 0:2e5e65a6fb30 153 pc.printf("Gyroscope sensitivity is %f LSB/deg/s \n\r", 1.0f/gRes);
onehorse 0:2e5e65a6fb30 154 pc.printf("Magnetometer sensitivity is %f LSB/G \n\r", 1.0f/mRes);
soulx 3:3e04c1c03cab 155 // pc.printf("Magnetometer[0] adjust sensittivity is %f \n\r", magCalibration[0]);
soulx 3:3e04c1c03cab 156 // pc.printf("Magnetometer[1] adjust sensittivity is %f \n\r", magCalibration[1]);
soulx 3:3e04c1c03cab 157 // pc.printf("Magnetometer[2] adjust sensittivity is %f \n\r", magCalibration[2]);
soulx 3:3e04c1c03cab 158 // mRes = 10.*1229./4096.; // Conversion from 1229 microTesla full scale (4096) to 12.29 Gauss full scale
soulx 3:3e04c1c03cab 159 //mRes = 10.*1229./32760.;
soulx 3:3e04c1c03cab 160 // So far, magnetometer bias is calculated and subtracted here manually, should construct an algorithm to do it automatically
soulx 3:3e04c1c03cab 161 // like the gyro and accelerometer biases
soulx 3:3e04c1c03cab 162 //magbias[0] = -5.; // User environmental x-axis correction in milliGauss
soulx 3:3e04c1c03cab 163 //magbias[1] = -95.; // User environmental y-axis correction in milliGauss
soulx 3:3e04c1c03cab 164 //magbias[2] = -260.; // User environmental z-axis correction in milliGauss
soulx 3:3e04c1c03cab 165
soulx 3:3e04c1c03cab 166 // magbias[0] = +470.; // User environmental x-axis correction in milliGauss, should be automatically calculated
soulx 3:3e04c1c03cab 167 // magbias[1] = +120.; // User environmental x-axis correction in milliGauss
soulx 3:3e04c1c03cab 168 // magbias[2] = +125.; // User environmental x-axis correction in milliGauss
soulx 3:3e04c1c03cab 169
soulx 3:3e04c1c03cab 170
soulx 3:3e04c1c03cab 171
soulx 3:3e04c1c03cab 172 pc.printf("START scan mag\n\r\n\r\n\r");
soulx 3:3e04c1c03cab 173 //wait(1);
soulx 3:3e04c1c03cab 174 for(int i=0; i<800; i++) {
soulx 3:3e04c1c03cab 175 mpu9250.readMagData(magCount);
soulx 3:3e04c1c03cab 176
soulx 3:3e04c1c03cab 177 if(magCount[0]<xmin)
soulx 3:3e04c1c03cab 178 xmin = magCount[0];
soulx 3:3e04c1c03cab 179 if(magCount[0]>xmax)
soulx 3:3e04c1c03cab 180 xmax = magCount[0];
onehorse 0:2e5e65a6fb30 181
soulx 3:3e04c1c03cab 182 if(magCount[1]<ymin)
soulx 3:3e04c1c03cab 183 ymin = magCount[1];
soulx 3:3e04c1c03cab 184 if(magCount[1]>ymax)
soulx 3:3e04c1c03cab 185 ymax = magCount[1];
soulx 3:3e04c1c03cab 186
soulx 3:3e04c1c03cab 187 if(magCount[2]<zmin)
soulx 3:3e04c1c03cab 188 zmin = magCount[2];
soulx 3:3e04c1c03cab 189 if(mz>zmax)
soulx 3:3e04c1c03cab 190 zmax = mz;
soulx 3:3e04c1c03cab 191
soulx 3:3e04c1c03cab 192
soulx 3:3e04c1c03cab 193
soulx 3:3e04c1c03cab 194 wait_ms(10);
soulx 3:3e04c1c03cab 195 }
soulx 3:3e04c1c03cab 196 pc.printf("FINISH scan\r\n\r\n");
soulx 3:3e04c1c03cab 197 pc.printf("Mx Max= %f Min= %f\n\r",xmax,xmin);
soulx 3:3e04c1c03cab 198 pc.printf("My Max= %f Min= %f\n\r",ymax,ymin);
soulx 3:3e04c1c03cab 199 pc.printf("Mz Max= %f Min= %f\n\r",zmax,zmin);
soulx 3:3e04c1c03cab 200
soulx 3:3e04c1c03cab 201
soulx 3:3e04c1c03cab 202
soulx 3:3e04c1c03cab 203 magbias[0] = ((xmax-xmin)/2.0f - xmax); // User environmental x-axis correction in milliGauss, should be automatically calculated
soulx 3:3e04c1c03cab 204 magbias[1] = ((ymax-ymin)/2.0f - ymax); // User environmental x-axis correction in milliGauss
soulx 3:3e04c1c03cab 205 magbias[2] = ((zmax-zmin)/2.0f - zmax); // User environmental x-axis correction in milliGauss
soulx 3:3e04c1c03cab 206
soulx 3:3e04c1c03cab 207 //magbias[0] = (xmin-xmax)/2.0f; // User environmental x-axis correction in milliGauss, should be automatically calculated
soulx 3:3e04c1c03cab 208 //magbias[1] = (ymin-ymax)/2.0f; // User environmental x-axis correction in milliGauss
soulx 3:3e04c1c03cab 209 //magbias[2] = (zmin-zmax)/2.0f; // User environmental x-axis correction in milliGauss
soulx 3:3e04c1c03cab 210 pc.printf("mag[0] %f",magbias[0]);
soulx 3:3e04c1c03cab 211 pc.printf("mag[1] %f",magbias[1]);
soulx 3:3e04c1c03cab 212 pc.printf("mag[2] %f\n\r",magbias[2]);
soulx 3:3e04c1c03cab 213 // resalt = atan(magY+((yMin-yMax)/2),magX+(xMin-xMax)/2))*180/PI;
onehorse 0:2e5e65a6fb30 214
soulx 3:3e04c1c03cab 215
soulx 3:3e04c1c03cab 216 while(1) {
soulx 3:3e04c1c03cab 217
soulx 3:3e04c1c03cab 218 // If intPin goes high, all data registers have new data
soulx 3:3e04c1c03cab 219 if(mpu9250.readByte(MPU9250_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt
soulx 3:3e04c1c03cab 220
soulx 3:3e04c1c03cab 221 mpu9250.readAccelData(accelCount); // Read the x/y/z adc values
soulx 3:3e04c1c03cab 222 // Now we'll calculate the accleration value into actual g's
soulx 3:3e04c1c03cab 223 ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set
soulx 3:3e04c1c03cab 224 ay = (float)accelCount[1]*aRes - accelBias[1];
soulx 3:3e04c1c03cab 225 az = (float)accelCount[2]*aRes - accelBias[2];
soulx 3:3e04c1c03cab 226
soulx 3:3e04c1c03cab 227 mpu9250.readGyroData(gyroCount); // Read the x/y/z adc values
soulx 3:3e04c1c03cab 228 // Calculate the gyro value into actual degrees per second
soulx 3:3e04c1c03cab 229 gx = (float)gyroCount[0]*gRes - gyroBias[0]; // get actual gyro value, this depends on scale being set
soulx 3:3e04c1c03cab 230 gy = (float)gyroCount[1]*gRes - gyroBias[1];
soulx 3:3e04c1c03cab 231 gz = (float)gyroCount[2]*gRes - gyroBias[2];
soulx 3:3e04c1c03cab 232
soulx 3:3e04c1c03cab 233 mpu9250.readMagData(magCount); // Read the x/y/z adc values
soulx 3:3e04c1c03cab 234 // Calculate the magnetometer values in milliGauss
soulx 3:3e04c1c03cab 235 // Include factory calibration per data sheet and user environmental corrections
soulx 3:3e04c1c03cab 236 /* if(magCount[0]<xmin)
soulx 3:3e04c1c03cab 237 xmin = magCount[0];
soulx 3:3e04c1c03cab 238 if(magCount[0]>xmax)
soulx 3:3e04c1c03cab 239 xmax = magCount[0];
soulx 3:3e04c1c03cab 240
soulx 3:3e04c1c03cab 241 if(magCount[1]<ymin)
soulx 3:3e04c1c03cab 242 ymin = magCount[1];
soulx 3:3e04c1c03cab 243 if(magCount[1]>ymax)
soulx 3:3e04c1c03cab 244 ymax = magCount[1];
soulx 3:3e04c1c03cab 245
soulx 3:3e04c1c03cab 246 if(magCount[2]<zmin)
soulx 3:3e04c1c03cab 247 zmin = magCount[2];
soulx 3:3e04c1c03cab 248 if(mz>zmax)
soulx 3:3e04c1c03cab 249 zmax = mz;
soulx 3:3e04c1c03cab 250 wait_ms(1);
soulx 3:3e04c1c03cab 251 */
soulx 3:3e04c1c03cab 252 // pc.printf("FINISH scan\r\n\r\n");
soulx 3:3e04c1c03cab 253
soulx 3:3e04c1c03cab 254 mx = (float)magCount[0]*mRes*magCalibration[0] + magbias[0]; // get actual magnetometer value, this depends on scale being set
soulx 3:3e04c1c03cab 255 my = (float)magCount[1]*mRes*magCalibration[1] + magbias[1];
soulx 3:3e04c1c03cab 256 mz = (float)magCount[2]*mRes*magCalibration[2] + magbias[2];
soulx 3:3e04c1c03cab 257
soulx 3:3e04c1c03cab 258 // mx = (float)magCount[0]*1.499389499f - magbias[0]; // get actual magnetometer value, this depends on scale being set
soulx 3:3e04c1c03cab 259 // my = (float)magCount[1]*1.499389499f - magbias[1];
soulx 3:3e04c1c03cab 260 // mz = (float)magCount[2]*1.499389499f - magbias[2];
soulx 3:3e04c1c03cab 261
soulx 3:3e04c1c03cab 262
soulx 3:3e04c1c03cab 263
soulx 3:3e04c1c03cab 264
soulx 3:3e04c1c03cab 265 }
soulx 3:3e04c1c03cab 266
soulx 3:3e04c1c03cab 267 Now = t.read_us();
soulx 3:3e04c1c03cab 268 deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update
soulx 3:3e04c1c03cab 269 lastUpdate = Now;
soulx 3:3e04c1c03cab 270
soulx 3:3e04c1c03cab 271 sum += deltat;
soulx 3:3e04c1c03cab 272 sumCount++;
soulx 3:3e04c1c03cab 273
onehorse 0:2e5e65a6fb30 274 // if(lastUpdate - firstUpdate > 10000000.0f) {
onehorse 0:2e5e65a6fb30 275 // beta = 0.04; // decrease filter gain after stabilized
onehorse 0:2e5e65a6fb30 276 // zeta = 0.015; // increasey bias drift gain after stabilized
soulx 3:3e04c1c03cab 277 // }
soulx 3:3e04c1c03cab 278
soulx 3:3e04c1c03cab 279 // Pass gyro rate as rad/s
soulx 3:3e04c1c03cab 280 mpu9250.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
soulx 3:3e04c1c03cab 281 // mpu9250.MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
soulx 3:3e04c1c03cab 282
soulx 3:3e04c1c03cab 283 // Serial print and/or display at 0.5 s rate independent of data rates
soulx 3:3e04c1c03cab 284 delt_t = t.read_ms() - count;
soulx 3:3e04c1c03cab 285 if (delt_t > 500) { // update LCD once per half-second independent of read rate
soulx 3:3e04c1c03cab 286
soulx 3:3e04c1c03cab 287 pc.printf("ax = %f", 1000*ax);
soulx 3:3e04c1c03cab 288 pc.printf(" ay = %f", 1000*ay);
soulx 3:3e04c1c03cab 289 pc.printf(" az = %f mg\n\r", 1000*az);
onehorse 0:2e5e65a6fb30 290
soulx 3:3e04c1c03cab 291 pc.printf("gx = %f", gx);
soulx 3:3e04c1c03cab 292 pc.printf(" gy = %f", gy);
soulx 3:3e04c1c03cab 293 pc.printf(" gz = %f deg/s\n\r", gz);
soulx 3:3e04c1c03cab 294
soulx 3:3e04c1c03cab 295 pc.printf("mx = %f", mx);
soulx 3:3e04c1c03cab 296 pc.printf(" my = %f", my);
soulx 3:3e04c1c03cab 297 pc.printf(" mz = %f mG\n\r", mz);
onehorse 0:2e5e65a6fb30 298
soulx 3:3e04c1c03cab 299 whoami = mpu9250.readByte(AK8963_ADDRESS, AK8963_ST2); // Read WHO_AM_I register for MPU-9250
soulx 3:3e04c1c03cab 300 // pc.printf("I AM 0x%x\n\r", whoami); pc.printf("I SHOULD BE 0x10\n\r");
soulx 3:3e04c1c03cab 301 if(whoami == 0x14) {
soulx 3:3e04c1c03cab 302 pc.printf("I AM 0x%x\n\r", whoami);
soulx 3:3e04c1c03cab 303 while(1);
soulx 3:3e04c1c03cab 304 }
soulx 3:3e04c1c03cab 305
soulx 3:3e04c1c03cab 306
soulx 3:3e04c1c03cab 307 tempCount = mpu9250.readTempData(); // Read the adc values
soulx 3:3e04c1c03cab 308 temperature = ((float) tempCount) / 333.87f + 21.0f; // Temperature in degrees Centigrade
soulx 3:3e04c1c03cab 309 //pc.printf(" temperature = %f C\n\r", temperature);
onehorse 0:2e5e65a6fb30 310
soulx 3:3e04c1c03cab 311 // pc.printf("q0 = %f\n\r", q[0]);
soulx 3:3e04c1c03cab 312 // pc.printf("q1 = %f\n\r", q[1]);
soulx 3:3e04c1c03cab 313 // pc.printf("q2 = %f\n\r", q[2]);
soulx 3:3e04c1c03cab 314 // pc.printf("q3 = %f\n\r", q[3]);
onehorse 0:2e5e65a6fb30 315
soulx 3:3e04c1c03cab 316 // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation.
soulx 3:3e04c1c03cab 317 // In this coordinate system, the positive z-axis is down toward Earth.
soulx 3:3e04c1c03cab 318 // 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.
soulx 3:3e04c1c03cab 319 // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative.
soulx 3:3e04c1c03cab 320 // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll.
soulx 3:3e04c1c03cab 321 // These arise from the definition of the homogeneous rotation matrix constructed from quaternions.
soulx 3:3e04c1c03cab 322 // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be
soulx 3:3e04c1c03cab 323 // applied in the correct order which for this configuration is yaw, pitch, and then roll.
soulx 3:3e04c1c03cab 324 // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links.
soulx 3:3e04c1c03cab 325 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]);
soulx 3:3e04c1c03cab 326 pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
soulx 3:3e04c1c03cab 327 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]);
soulx 3:3e04c1c03cab 328
soulx 3:3e04c1c03cab 329 float Xh = mx*cos(pitch)+my*sin(roll)*sin(pitch)-mz*cos(roll)*sin(pitch);
soulx 3:3e04c1c03cab 330 float Yh = my*cos(roll)+mz*sin(roll);
soulx 3:3e04c1c03cab 331
soulx 3:3e04c1c03cab 332 float yawmag = atan2(Yh,Xh)+PI;
soulx 3:3e04c1c03cab 333 pc.printf("Xh= %f Yh= %f ",Xh,Yh);
soulx 3:3e04c1c03cab 334 pc.printf("Yaw[mag]= %f\n\r",yawmag*180.0f/PI);
soulx 3:3e04c1c03cab 335
soulx 3:3e04c1c03cab 336
soulx 3:3e04c1c03cab 337
soulx 3:3e04c1c03cab 338 pitch *= 180.0f / PI;
soulx 3:3e04c1c03cab 339 yaw *= 180.0f / PI;
soulx 3:3e04c1c03cab 340 yaw += 180.0f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04
soulx 3:3e04c1c03cab 341 roll *= 180.0f / PI;
soulx 3:3e04c1c03cab 342
soulx 3:3e04c1c03cab 343 pc.printf("Yaw, Pitch, Roll: %f %f %f\n\r", yaw, pitch, roll);
soulx 3:3e04c1c03cab 344 pc.printf("average rate = %f\n\r", (float) sumCount/sum);
onehorse 0:2e5e65a6fb30 345 // sprintf(buffer, "YPR: %f %f %f", yaw, pitch, roll);
onehorse 0:2e5e65a6fb30 346 // lcd.printString(buffer, 0, 4);
onehorse 0:2e5e65a6fb30 347 // sprintf(buffer, "rate = %f", (float) sumCount/sum);
onehorse 0:2e5e65a6fb30 348 // lcd.printString(buffer, 0, 5);
soulx 3:3e04c1c03cab 349
soulx 3:3e04c1c03cab 350
soulx 3:3e04c1c03cab 351
soulx 3:3e04c1c03cab 352
soulx 3:3e04c1c03cab 353 myled= !myled;
soulx 3:3e04c1c03cab 354 count = t.read_ms();
onehorse 0:2e5e65a6fb30 355
soulx 3:3e04c1c03cab 356 if(count > 1<<21) {
soulx 3:3e04c1c03cab 357 t.start(); // start the timer over again if ~30 minutes has passed
soulx 3:3e04c1c03cab 358 count = 0;
soulx 3:3e04c1c03cab 359 deltat= 0;
soulx 3:3e04c1c03cab 360 lastUpdate = t.read_us();
soulx 3:3e04c1c03cab 361 }
soulx 3:3e04c1c03cab 362 sum = 0;
soulx 3:3e04c1c03cab 363 sumCount = 0;
soulx 3:3e04c1c03cab 364 }
onehorse 0:2e5e65a6fb30 365 }
onehorse 0:2e5e65a6fb30 366 }