This program is designed to run on a set of Xadow M0 modules to create a Hotshoe IMU which outputs GPS and Orientation data to Nikon cameras, as well as triggering the camera at set intervals.

Dependencies:   MBed_Adafruit-GPS-Library SC16IS750 SDFileSystem SSD1308_128x64_I2C USBDevice mbed BMP085

Fork of MPU9150AHRS by Kris Winer

/media/uploads/whatnick/20151022_004759.jpg

Committer:
whatnick
Date:
Sun Dec 28 13:42:23 2014 +0000
Revision:
3:c9267f465464
Parent:
2:f1912528eeaf
Child:
4:256505da4487
Change Baud rate.

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
whatnick 1:9de6ac4b381d 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.
whatnick 1:9de6ac4b381d 6
whatnick 1:9de6ac4b381d 7 Demonstrate basic MPU-9150 functionality including parameterizing the register addresses, initializing the sensor,
whatnick 1:9de6ac4b381d 8 getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to
whatnick 1:9de6ac4b381d 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.
whatnick 1:9de6ac4b381d 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.
whatnick 1:9de6ac4b381d 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
whatnick 1:9de6ac4b381d 22
whatnick 1:9de6ac4b381d 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 */
whatnick 1:9de6ac4b381d 28
whatnick 1:9de6ac4b381d 29 //#include "ST_F401_84MHZ.h"
onehorse 0:39935bb3c1a1 30 //F401_init84 myinit(0);
onehorse 0:39935bb3c1a1 31 #include "mbed.h"
whatnick 1:9de6ac4b381d 32 #include "mbed_logo.h"
onehorse 0:39935bb3c1a1 33 #include "MPU9150.h"
whatnick 1:9de6ac4b381d 34 #include "SSD1308.h"
whatnick 1:9de6ac4b381d 35 #include "SDFileSystem.h"
whatnick 2:f1912528eeaf 36 #include "MBed_Adafruit_GPS.h"
whatnick 2:f1912528eeaf 37 #include "SC16IS750.h"
onehorse 0:39935bb3c1a1 38
whatnick 1:9de6ac4b381d 39 //Use Xadow OLED for display
whatnick 1:9de6ac4b381d 40 SSD1308 oled = SSD1308(i2c, SSD1308_SA0);
whatnick 1:9de6ac4b381d 41
whatnick 2:f1912528eeaf 42 //Use Serial expander for extra UART
whatnick 2:f1912528eeaf 43 SC16IS750_I2C serial_i2c(&i2c, SC16IS750_SA5);
whatnick 2:f1912528eeaf 44
whatnick 1:9de6ac4b381d 45 SDFileSystem sd(P0_21, P0_22, P1_15, P1_19, "sd", P0_20, SDFileSystem::SWITCH_POS_NC); // the pinout on the mbed Cool Components workshop board
onehorse 0:39935bb3c1a1 46
onehorse 0:39935bb3c1a1 47 float sum = 0;
onehorse 0:39935bb3c1a1 48 uint32_t sumCount = 0, mcount = 0;
whatnick 1:9de6ac4b381d 49 char buffer[32];
whatnick 1:9de6ac4b381d 50
whatnick 1:9de6ac4b381d 51 MPU9150 MPU9150;
onehorse 0:39935bb3c1a1 52
whatnick 1:9de6ac4b381d 53 Timer t;
whatnick 1:9de6ac4b381d 54
whatnick 1:9de6ac4b381d 55 Serial gps(P0_19,P0_18);
onehorse 0:39935bb3c1a1 56
whatnick 2:f1912528eeaf 57 //#define DEBUG
onehorse 0:39935bb3c1a1 58
whatnick 1:9de6ac4b381d 59 #ifdef DEBUG
whatnick 1:9de6ac4b381d 60 #include "USBSerial.h" // To use USB virtual serial, a driver is needed, check http://mbed.org/handbook/USBSerial
whatnick 1:9de6ac4b381d 61 #define LOG(args...) pc.printf(args)
whatnick 1:9de6ac4b381d 62 USBSerial pc;
whatnick 1:9de6ac4b381d 63 #else
whatnick 1:9de6ac4b381d 64 #define LOG(args...)
whatnick 1:9de6ac4b381d 65 #endif
onehorse 0:39935bb3c1a1 66
onehorse 0:39935bb3c1a1 67 int main()
onehorse 0:39935bb3c1a1 68 {
whatnick 1:9de6ac4b381d 69
whatnick 1:9de6ac4b381d 70 //Set up I2C
whatnick 1:9de6ac4b381d 71 i2c.frequency(400000); // use fast (400 kHz) I2C
whatnick 1:9de6ac4b381d 72
whatnick 2:f1912528eeaf 73 //Set up GPS
whatnick 2:f1912528eeaf 74 Adafruit_GPS myGPS(&gps);
whatnick 2:f1912528eeaf 75 char c; //when read via Adafruit_GPS::read(), the class returns single character stored here
whatnick 1:9de6ac4b381d 76
whatnick 2:f1912528eeaf 77 LOG("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock);
onehorse 0:39935bb3c1a1 78
whatnick 1:9de6ac4b381d 79 t.start();
whatnick 1:9de6ac4b381d 80
whatnick 2:f1912528eeaf 81 myGPS.begin(9600);
whatnick 3:c9267f465464 82 //Set BLE baudrate
whatnick 3:c9267f465464 83 serial_i2c.baud(9600);
whatnick 3:c9267f465464 84 serial_i2c.printf("AT+BAUD6");
whatnick 3:c9267f465464 85 wait(1)h
whatnick 2:f1912528eeaf 86 serial_i2c.baud(4800);
whatnick 1:9de6ac4b381d 87 oled.fillDisplay(0xAA);
whatnick 1:9de6ac4b381d 88 oled.setDisplayOff();
onehorse 0:39935bb3c1a1 89 wait(1);
whatnick 1:9de6ac4b381d 90 oled.setDisplayOn();
whatnick 1:9de6ac4b381d 91
whatnick 1:9de6ac4b381d 92 oled.clearDisplay();
whatnick 1:9de6ac4b381d 93 oled.setDisplayInverse();
whatnick 1:9de6ac4b381d 94 wait(0.5);
whatnick 1:9de6ac4b381d 95 oled.setDisplayNormal();
whatnick 1:9de6ac4b381d 96
whatnick 1:9de6ac4b381d 97 oled.writeBitmap((uint8_t*) mbed_logo);
whatnick 1:9de6ac4b381d 98
whatnick 2:f1912528eeaf 99 LOG("OLED test done\r\n");
whatnick 1:9de6ac4b381d 100 wait(10);
whatnick 1:9de6ac4b381d 101 oled.clearDisplay();
whatnick 1:9de6ac4b381d 102
whatnick 2:f1912528eeaf 103 oled.writeString(0, 0, "##AeroAHRS##");
whatnick 1:9de6ac4b381d 104 // Read the WHO_AM_I register, this is a good test of communication
whatnick 1:9de6ac4b381d 105 uint8_t whoami = MPU9150.readByte(MPU9150_ADDRESS, WHO_AM_I_MPU9150); // Read WHO_AM_I register for MPU-9250
whatnick 2:f1912528eeaf 106 LOG("I AM 0x%x\n\r", whoami);
whatnick 2:f1912528eeaf 107 LOG("I SHOULD BE 0x68\n\r");
whatnick 1:9de6ac4b381d 108
whatnick 1:9de6ac4b381d 109 if (whoami == 0x68) { // WHO_AM_I should be 0x68
whatnick 2:f1912528eeaf 110 LOG("MPU9150 WHO_AM_I is 0x%x\n\r", whoami);
whatnick 2:f1912528eeaf 111 LOG("MPU9150 is online...\n\r");
whatnick 1:9de6ac4b381d 112 //lcd.clear();
whatnick 1:9de6ac4b381d 113 //lcd.printString("MPU9150 is", 0, 0);
whatnick 1:9de6ac4b381d 114 //sprintf(buffer, "0x%x", whoami);
whatnick 1:9de6ac4b381d 115 //lcd.printString(buffer, 0, 1);
whatnick 1:9de6ac4b381d 116 //lcd.printString("shoud be 0x68", 0, 2);
whatnick 1:9de6ac4b381d 117 wait(1);
whatnick 1:9de6ac4b381d 118
whatnick 1:9de6ac4b381d 119 MPU9150.MPU9150SelfTest(SelfTest);
whatnick 2:f1912528eeaf 120 LOG("x-axis self test: acceleration trim within %f % of factory value\n\r", SelfTest[0]);
whatnick 2:f1912528eeaf 121 LOG("y-axis self test: acceleration trim within %f % of factory value\n\r", SelfTest[1]);
whatnick 2:f1912528eeaf 122 LOG("z-axis self test: acceleration trim within %f % of factory value\n\r", SelfTest[2]);
whatnick 2:f1912528eeaf 123 LOG("x-axis self test: gyration trim within %f % of factory value\n\r", SelfTest[3]);
whatnick 2:f1912528eeaf 124 LOG("y-axis self test: gyration trim within %f % of factory value\n\r", SelfTest[4]);
whatnick 2:f1912528eeaf 125 LOG("z-axis self test: gyration trim within %f % of factory value\n\r", SelfTest[5]);
whatnick 1:9de6ac4b381d 126 wait(1);
whatnick 1:9de6ac4b381d 127 MPU9150.resetMPU9150(); // Reset registers to default in preparation for device calibration
whatnick 1:9de6ac4b381d 128 MPU9150.calibrateMPU9150(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers
whatnick 2:f1912528eeaf 129 LOG("x gyro bias = %f\n\r", gyroBias[0]);
whatnick 2:f1912528eeaf 130 LOG("y gyro bias = %f\n\r", gyroBias[1]);
whatnick 2:f1912528eeaf 131 LOG("z gyro bias = %f\n\r", gyroBias[2]);
whatnick 2:f1912528eeaf 132 LOG("x accel bias = %f\n\r", accelBias[0]);
whatnick 2:f1912528eeaf 133 LOG("y accel bias = %f\n\r", accelBias[1]);
whatnick 2:f1912528eeaf 134 LOG("z accel bias = %f\n\r", accelBias[2]);
whatnick 1:9de6ac4b381d 135 wait(1);
whatnick 1:9de6ac4b381d 136 MPU9150.initMPU9150();
whatnick 2:f1912528eeaf 137 LOG("MPU9150 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature
whatnick 1:9de6ac4b381d 138 MPU9150.initAK8975A(magCalibration);
whatnick 2:f1912528eeaf 139 LOG("AK8975 initialized for active data mode....\n\r"); // Initialize device for active mode read of magnetometer
whatnick 1:9de6ac4b381d 140 } else {
whatnick 2:f1912528eeaf 141 LOG("Could not connect to MPU9150: \n\r");
whatnick 2:f1912528eeaf 142 LOG("%#x \n", whoami);
whatnick 1:9de6ac4b381d 143
whatnick 1:9de6ac4b381d 144 //lcd.clear();
whatnick 1:9de6ac4b381d 145 //lcd.printString("MPU9150", 0, 0);
whatnick 1:9de6ac4b381d 146 //lcd.printString("no connection", 0, 1);
whatnick 1:9de6ac4b381d 147 sprintf(buffer, "WHO_AM_I 0x%x", whoami);
whatnick 1:9de6ac4b381d 148 //lcd.printString(buffer, 0, 2);
whatnick 1:9de6ac4b381d 149
whatnick 1:9de6ac4b381d 150 while(1) ; // Loop forever if communication doesn't happen
onehorse 0:39935bb3c1a1 151 }
onehorse 0:39935bb3c1a1 152
onehorse 0:39935bb3c1a1 153 uint8_t MagRate = 10; // set magnetometer read rate in Hz; 10 to 100 (max) Hz are reasonable values
onehorse 0:39935bb3c1a1 154 MPU9150.getAres(); // Get accelerometer sensitivity
onehorse 0:39935bb3c1a1 155 MPU9150.getGres(); // Get gyro sensitivity
onehorse 0:39935bb3c1a1 156 mRes = 10.*1229./4096.; // Conversion from 1229 microTesla full scale (4096) to 12.29 Gauss full scale
onehorse 0:39935bb3c1a1 157 // So far, magnetometer bias is calculated and subtracted here manually, should construct an algorithm to do it automatically
onehorse 0:39935bb3c1a1 158 // like the gyro and accelerometer biases
onehorse 0:39935bb3c1a1 159 magbias[0] = -5.; // User environmental x-axis correction in milliGauss
onehorse 0:39935bb3c1a1 160 magbias[1] = -95.; // User environmental y-axis correction in milliGauss
onehorse 0:39935bb3c1a1 161 magbias[2] = -260.; // User environmental z-axis correction in milliGauss
whatnick 1:9de6ac4b381d 162
whatnick 2:f1912528eeaf 163 //Wait for GPS to acquire lock
whatnick 2:f1912528eeaf 164 oled.writeString(2,0,"GPS Init ");
whatnick 2:f1912528eeaf 165 while(!myGPS.fix) {
whatnick 2:f1912528eeaf 166 c = myGPS.read(); //queries the GPS
whatnick 2:f1912528eeaf 167 if (c) {
whatnick 2:f1912528eeaf 168 LOG("%c", c); //this line will echo the GPS data if not paused
whatnick 2:f1912528eeaf 169 }
whatnick 2:f1912528eeaf 170
whatnick 2:f1912528eeaf 171 //check if we recieved a new message from GPS, if so, attempt to parse it,
whatnick 2:f1912528eeaf 172 if ( myGPS.newNMEAreceived() ) {
whatnick 2:f1912528eeaf 173 if ( !myGPS.parse(myGPS.lastNMEA()) ) {
whatnick 2:f1912528eeaf 174 continue;
whatnick 2:f1912528eeaf 175 }
whatnick 2:f1912528eeaf 176 }
whatnick 2:f1912528eeaf 177 }
whatnick 2:f1912528eeaf 178
whatnick 1:9de6ac4b381d 179 mkdir("/sd/logdir", 0777);
whatnick 2:f1912528eeaf 180 sprintf(buffer,"/sd/logdir/%d%d20%d_%d%d%d.txt",myGPS.day, myGPS.month, myGPS.year,
whatnick 2:f1912528eeaf 181 myGPS.hour, myGPS.minute, myGPS.seconds);
whatnick 2:f1912528eeaf 182 FILE *fp = fopen(buffer, "w");
whatnick 1:9de6ac4b381d 183 if(fp == NULL) {
whatnick 1:9de6ac4b381d 184 LOG("Could not open file for write\n");
whatnick 1:9de6ac4b381d 185 oled.writeString(7,0,"SD Fail");
whatnick 2:f1912528eeaf 186 } else {
whatnick 2:f1912528eeaf 187 oled.writeString(7,0,"SD OKAY");
whatnick 1:9de6ac4b381d 188 }
onehorse 0:39935bb3c1a1 189
whatnick 1:9de6ac4b381d 190 while(1) {
whatnick 1:9de6ac4b381d 191
whatnick 1:9de6ac4b381d 192 // If intPin goes high, all data registers have new data
whatnick 1:9de6ac4b381d 193 if(MPU9150.readByte(MPU9150_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt
whatnick 1:9de6ac4b381d 194
whatnick 1:9de6ac4b381d 195 MPU9150.readAccelData(accelCount); // Read the x/y/z adc values
whatnick 1:9de6ac4b381d 196 // Now we'll calculate the accleration value into actual g's
whatnick 1:9de6ac4b381d 197 ax = (float)accelCount[0]*aRes; // - accelBias[0]; // get actual g value, this depends on scale being set
whatnick 1:9de6ac4b381d 198 ay = (float)accelCount[1]*aRes; // - accelBias[1];
whatnick 1:9de6ac4b381d 199 az = (float)accelCount[2]*aRes; // - accelBias[2];
onehorse 0:39935bb3c1a1 200
whatnick 1:9de6ac4b381d 201 MPU9150.readGyroData(gyroCount); // Read the x/y/z adc values
whatnick 1:9de6ac4b381d 202 // Calculate the gyro value into actual degrees per second
whatnick 1:9de6ac4b381d 203 gx = (float)gyroCount[0]*gRes; // - gyroBias[0]; // get actual gyro value, this depends on scale being set
whatnick 1:9de6ac4b381d 204 gy = (float)gyroCount[1]*gRes; // - gyroBias[1];
whatnick 1:9de6ac4b381d 205 gz = (float)gyroCount[2]*gRes; // - gyroBias[2];
whatnick 1:9de6ac4b381d 206
whatnick 1:9de6ac4b381d 207 mcount++;
whatnick 1:9de6ac4b381d 208 if (mcount > 200/MagRate) { // this is a poor man's way of setting the magnetometer read rate (see below)
whatnick 1:9de6ac4b381d 209 MPU9150.readMagData(magCount); // Read the x/y/z adc values
whatnick 1:9de6ac4b381d 210 // Calculate the magnetometer values in milliGauss
whatnick 1:9de6ac4b381d 211 // Include factory calibration per data sheet and user environmental corrections
whatnick 1:9de6ac4b381d 212 mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0]; // get actual magnetometer value, this depends on scale being set
whatnick 1:9de6ac4b381d 213 my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1];
whatnick 1:9de6ac4b381d 214 mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2];
whatnick 1:9de6ac4b381d 215 mcount = 0;
whatnick 1:9de6ac4b381d 216 }
whatnick 1:9de6ac4b381d 217 }
whatnick 1:9de6ac4b381d 218
whatnick 2:f1912528eeaf 219 //Handle GPS data
whatnick 2:f1912528eeaf 220 {
whatnick 2:f1912528eeaf 221 c = myGPS.read(); //queries the GPS
whatnick 2:f1912528eeaf 222 if (c) {
whatnick 2:f1912528eeaf 223 LOG("%c", c); //this line will echo the GPS data if not paused
whatnick 2:f1912528eeaf 224 }
whatnick 2:f1912528eeaf 225
whatnick 2:f1912528eeaf 226 //check if we recieved a new message from GPS, if so, attempt to parse it,
whatnick 2:f1912528eeaf 227 if ( myGPS.newNMEAreceived() ) {
whatnick 2:f1912528eeaf 228 if ( !myGPS.parse(myGPS.lastNMEA()) ) {
whatnick 2:f1912528eeaf 229 continue;
whatnick 2:f1912528eeaf 230 }
whatnick 2:f1912528eeaf 231 else
whatnick 2:f1912528eeaf 232 {
whatnick 2:f1912528eeaf 233 serial_i2c.printf(myGPS.lastNMEA());
whatnick 2:f1912528eeaf 234 }
whatnick 2:f1912528eeaf 235 }
whatnick 2:f1912528eeaf 236 }
whatnick 2:f1912528eeaf 237
whatnick 1:9de6ac4b381d 238 Now = t.read_us();
whatnick 1:9de6ac4b381d 239 deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update
whatnick 1:9de6ac4b381d 240 lastUpdate = Now;
whatnick 1:9de6ac4b381d 241
whatnick 1:9de6ac4b381d 242 sum += deltat;
whatnick 1:9de6ac4b381d 243 sumCount++;
whatnick 1:9de6ac4b381d 244
onehorse 0:39935bb3c1a1 245 // if(lastUpdate - firstUpdate > 10000000.0f) {
onehorse 0:39935bb3c1a1 246 // beta = 0.04; // decrease filter gain after stabilized
onehorse 0:39935bb3c1a1 247 // zeta = 0.015; // increasey bias drift gain after stabilized
whatnick 1:9de6ac4b381d 248 // }
whatnick 1:9de6ac4b381d 249
whatnick 1:9de6ac4b381d 250 // Pass gyro rate as rad/s
whatnick 1:9de6ac4b381d 251 MPU9150.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
whatnick 1:9de6ac4b381d 252 // MPU9150.MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
whatnick 1:9de6ac4b381d 253
whatnick 1:9de6ac4b381d 254 // Serial print and/or display at 0.5 s rate independent of data rates
whatnick 1:9de6ac4b381d 255 delt_t = t.read_ms() - count;
whatnick 1:9de6ac4b381d 256 if (delt_t > 500) { // update LCD once per half-second independent of read rate
whatnick 1:9de6ac4b381d 257
whatnick 2:f1912528eeaf 258 LOG("ax = %f", 1000*ax);
whatnick 2:f1912528eeaf 259 LOG(" ay = %f", 1000*ay);
whatnick 2:f1912528eeaf 260 LOG(" az = %f mg\n\r", 1000*az);
onehorse 0:39935bb3c1a1 261
whatnick 2:f1912528eeaf 262 LOG("gx = %f", gx);
whatnick 2:f1912528eeaf 263 LOG(" gy = %f", gy);
whatnick 2:f1912528eeaf 264 LOG(" gz = %f deg/s\n\r", gz);
whatnick 1:9de6ac4b381d 265
whatnick 2:f1912528eeaf 266 LOG("gx = %f", mx);
whatnick 2:f1912528eeaf 267 LOG(" gy = %f", my);
whatnick 2:f1912528eeaf 268 LOG(" gz = %f mG\n\r", mz);
onehorse 0:39935bb3c1a1 269
whatnick 1:9de6ac4b381d 270 tempCount = MPU9150.readTempData(); // Read the adc values
whatnick 1:9de6ac4b381d 271 temperature = ((float) tempCount) / 340.0f + 36.53f; // Temperature in degrees Centigrade
whatnick 2:f1912528eeaf 272 LOG(" temperature = %f C\n\r", temperature);
onehorse 0:39935bb3c1a1 273
whatnick 2:f1912528eeaf 274 LOG("q0 = %f\n\r", q[0]);
whatnick 2:f1912528eeaf 275 LOG("q1 = %f\n\r", q[1]);
whatnick 2:f1912528eeaf 276 LOG("q2 = %f\n\r", q[2]);
whatnick 2:f1912528eeaf 277 LOG("q3 = %f\n\r", q[3]);
whatnick 2:f1912528eeaf 278
whatnick 1:9de6ac4b381d 279 // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation.
whatnick 1:9de6ac4b381d 280 // In this coordinate system, the positive z-axis is down toward Earth.
whatnick 1:9de6ac4b381d 281 // 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.
whatnick 1:9de6ac4b381d 282 // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative.
whatnick 1:9de6ac4b381d 283 // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll.
whatnick 1:9de6ac4b381d 284 // These arise from the definition of the homogeneous rotation matrix constructed from quaternions.
whatnick 1:9de6ac4b381d 285 // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be
whatnick 1:9de6ac4b381d 286 // applied in the correct order which for this configuration is yaw, pitch, and then roll.
whatnick 1:9de6ac4b381d 287 // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links.
whatnick 1:9de6ac4b381d 288 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]);
whatnick 1:9de6ac4b381d 289 pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
whatnick 1:9de6ac4b381d 290 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]);
whatnick 1:9de6ac4b381d 291 pitch *= 180.0f / PI;
whatnick 1:9de6ac4b381d 292 yaw *= 180.0f / PI;
whatnick 1:9de6ac4b381d 293 yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04
whatnick 1:9de6ac4b381d 294 roll *= 180.0f / PI;
onehorse 0:39935bb3c1a1 295
whatnick 1:9de6ac4b381d 296
whatnick 2:f1912528eeaf 297 LOG("Yaw, Pitch, Roll: %f %f %f\n\r", yaw, pitch, roll);
whatnick 2:f1912528eeaf 298 LOG("average rate = %f\n\r", (float) sumCount/sum);
whatnick 2:f1912528eeaf 299
whatnick 2:f1912528eeaf 300 sprintf(buffer, "YPR:%3.0f %3.0f %3.0f", yaw, pitch, roll);
whatnick 1:9de6ac4b381d 301 oled.writeString(1,0,buffer);
whatnick 2:f1912528eeaf 302 if(fp != NULL) {
whatnick 2:f1912528eeaf 303 fprintf(fp,"YPR: %f %f %f\n", yaw, pitch, roll);
whatnick 2:f1912528eeaf 304 if(fflush(fp)==EOF) {
whatnick 2:f1912528eeaf 305 //SD card removed close file pointer
whatnick 2:f1912528eeaf 306 oled.writeString(7,0,"SD Fail");
whatnick 2:f1912528eeaf 307 fp=NULL;
whatnick 2:f1912528eeaf 308 }
whatnick 2:f1912528eeaf 309 }
whatnick 2:f1912528eeaf 310
whatnick 2:f1912528eeaf 311 LOG("Time: %d:%d:%d.%u\n", myGPS.hour, myGPS.minute, myGPS.seconds, myGPS.milliseconds);
whatnick 2:f1912528eeaf 312 LOG("Date: %d/%d/20%d\n", myGPS.day, myGPS.month, myGPS.year);
whatnick 2:f1912528eeaf 313 LOG("Fix: %d\n", (int) myGPS.fix);
whatnick 2:f1912528eeaf 314 LOG("Quality: %d\n", (int) myGPS.fixquality);
whatnick 2:f1912528eeaf 315 if (myGPS.fix) {
whatnick 2:f1912528eeaf 316 LOG("Location: %5.2f%c, %5.2f%c\n", myGPS.latitude, myGPS.lat, myGPS.longitude, myGPS.lon);
whatnick 2:f1912528eeaf 317 LOG("Speed: %5.2f knots\n", myGPS.speed);
whatnick 2:f1912528eeaf 318 LOG("Angle: %5.2f\n", myGPS.angle);
whatnick 2:f1912528eeaf 319 LOG("Altitude: %5.2f\n", myGPS.altitude);
whatnick 2:f1912528eeaf 320 LOG("Satellites: %d\n", myGPS.satellites);
whatnick 2:f1912528eeaf 321 }
whatnick 2:f1912528eeaf 322
whatnick 2:f1912528eeaf 323 if (myGPS.fix) {
whatnick 2:f1912528eeaf 324 sprintf(buffer,"LAT:%5.5f%c",myGPS.latitude,myGPS.lat);
whatnick 2:f1912528eeaf 325 oled.writeString(2,0,buffer);
whatnick 2:f1912528eeaf 326 sprintf(buffer,"LON:%5.5f%c",myGPS.longitude,myGPS.lon);
whatnick 2:f1912528eeaf 327 oled.writeString(3,0,buffer);
whatnick 2:f1912528eeaf 328 sprintf(buffer,"ALT:%5.2f",myGPS.altitude);
whatnick 2:f1912528eeaf 329 oled.writeString(4,0,buffer);
whatnick 2:f1912528eeaf 330 } else {
whatnick 2:f1912528eeaf 331 oled.writeString(2,0," ");
whatnick 2:f1912528eeaf 332 oled.writeString(2,0,"GPS Lost ");
whatnick 2:f1912528eeaf 333 oled.writeString(3,0," ");
whatnick 2:f1912528eeaf 334 oled.writeString(4,0," ");
whatnick 2:f1912528eeaf 335 }
whatnick 2:f1912528eeaf 336 sprintf(buffer,"Time: %d:%d:%d.%u\n", myGPS.hour, myGPS.minute, myGPS.seconds, myGPS.milliseconds);
whatnick 2:f1912528eeaf 337 oled.writeString(5,0,buffer);
whatnick 2:f1912528eeaf 338 sprintf(buffer,"Date: %d/%d/20%d\n", myGPS.day, myGPS.month, myGPS.year);
whatnick 2:f1912528eeaf 339 oled.writeString(6,0,buffer);
whatnick 2:f1912528eeaf 340
whatnick 2:f1912528eeaf 341 if(myGPS.fix && fp!=NULL) {
whatnick 2:f1912528eeaf 342 fprintf(fp,"LLA: %5.6f%c, %5.6f%c, %5.2f\n", myGPS.latitude, myGPS.lat, myGPS.longitude, myGPS.lon,myGPS.altitude);
whatnick 2:f1912528eeaf 343 }
whatnick 2:f1912528eeaf 344
whatnick 2:f1912528eeaf 345 if(fp != NULL) {
whatnick 2:f1912528eeaf 346 fprintf(fp,"DT: %d/%d/20%d %d:%d:%d.%u\n", myGPS.day, myGPS.month, myGPS.year, myGPS.hour, myGPS.minute, myGPS.seconds, myGPS.milliseconds);
whatnick 2:f1912528eeaf 347 if(fflush(fp)==EOF) {
whatnick 2:f1912528eeaf 348 //SD card removed close file pointer
whatnick 2:f1912528eeaf 349 oled.writeString(7,0,"SD Fail");
whatnick 2:f1912528eeaf 350 fp=NULL;
whatnick 2:f1912528eeaf 351 }
whatnick 2:f1912528eeaf 352 }
whatnick 2:f1912528eeaf 353
whatnick 2:f1912528eeaf 354 //if FP is null at the end of the loop attempt to open new log with fix
whatnick 2:f1912528eeaf 355 if(fp==NULL && myGPS.fix) {
whatnick 2:f1912528eeaf 356 mkdir("/sd/logdir", 0777);
whatnick 2:f1912528eeaf 357 sprintf(buffer,"/sd/logdir/%d%d20%d_%d%d%d.txt",myGPS.day, myGPS.month, myGPS.year,
whatnick 2:f1912528eeaf 358 myGPS.hour, myGPS.minute, myGPS.seconds);
whatnick 2:f1912528eeaf 359 FILE *fp = fopen(buffer, "w");
whatnick 2:f1912528eeaf 360 if(fp == NULL) {
whatnick 2:f1912528eeaf 361 LOG("Could not open file for write\n");
whatnick 2:f1912528eeaf 362 oled.writeString(7,0,"SD Fail");
whatnick 2:f1912528eeaf 363 } else {
whatnick 2:f1912528eeaf 364 oled.writeString(7,0,"SD OKAY");
whatnick 2:f1912528eeaf 365 }
whatnick 2:f1912528eeaf 366 }
whatnick 1:9de6ac4b381d 367
whatnick 1:9de6ac4b381d 368 myled= !myled;
whatnick 1:9de6ac4b381d 369 count = t.read_ms();
onehorse 0:39935bb3c1a1 370
whatnick 1:9de6ac4b381d 371 if(count > 1<<21) {
whatnick 1:9de6ac4b381d 372 t.start(); // start the timer over again if ~30 minutes has passed
whatnick 1:9de6ac4b381d 373 count = 0;
whatnick 1:9de6ac4b381d 374 deltat= 0;
whatnick 1:9de6ac4b381d 375 lastUpdate = t.read_us();
whatnick 1:9de6ac4b381d 376 }
whatnick 1:9de6ac4b381d 377 sum = 0;
whatnick 1:9de6ac4b381d 378 sumCount = 0;
whatnick 1:9de6ac4b381d 379 }
onehorse 0:39935bb3c1a1 380 }
whatnick 1:9de6ac4b381d 381
whatnick 1:9de6ac4b381d 382 }