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:
Mon May 25 02:51:01 2015 +0000
Revision:
5:81bba9f0f92b
Parent:
4:256505da4487
Child:
7:37bd00805530
Consolidation of sensors

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"
whatnick 5:81bba9f0f92b 38 #include "BMP085.h"
onehorse 0:39935bb3c1a1 39
whatnick 1:9de6ac4b381d 40 //Use Xadow OLED for display
whatnick 1:9de6ac4b381d 41 SSD1308 oled = SSD1308(i2c, SSD1308_SA0);
whatnick 1:9de6ac4b381d 42
whatnick 2:f1912528eeaf 43 //Use Serial expander for extra UART
whatnick 2:f1912528eeaf 44 SC16IS750_I2C serial_i2c(&i2c, SC16IS750_SA5);
whatnick 2:f1912528eeaf 45
whatnick 5:81bba9f0f92b 46 //Use BMP085 Temperature,Pressure
whatnick 5:81bba9f0f92b 47 BMP085 bmp(i2c);
whatnick 5:81bba9f0f92b 48
whatnick 1:9de6ac4b381d 49 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 50
onehorse 0:39935bb3c1a1 51 float sum = 0;
onehorse 0:39935bb3c1a1 52 uint32_t sumCount = 0, mcount = 0;
whatnick 5:81bba9f0f92b 53 char buffer[64];
whatnick 1:9de6ac4b381d 54
whatnick 1:9de6ac4b381d 55 MPU9150 MPU9150;
onehorse 0:39935bb3c1a1 56
whatnick 1:9de6ac4b381d 57 Timer t;
whatnick 1:9de6ac4b381d 58
whatnick 1:9de6ac4b381d 59 Serial gps(P0_19,P0_18);
onehorse 0:39935bb3c1a1 60
whatnick 2:f1912528eeaf 61 //#define DEBUG
onehorse 0:39935bb3c1a1 62
whatnick 1:9de6ac4b381d 63 #ifdef DEBUG
whatnick 1:9de6ac4b381d 64 #include "USBSerial.h" // To use USB virtual serial, a driver is needed, check http://mbed.org/handbook/USBSerial
whatnick 1:9de6ac4b381d 65 #define LOG(args...) pc.printf(args)
whatnick 1:9de6ac4b381d 66 USBSerial pc;
whatnick 1:9de6ac4b381d 67 #else
whatnick 1:9de6ac4b381d 68 #define LOG(args...)
whatnick 1:9de6ac4b381d 69 #endif
onehorse 0:39935bb3c1a1 70
whatnick 5:81bba9f0f92b 71 char checkSum(char* theseChars,int checkLen) {
whatnick 5:81bba9f0f92b 72 char check = 0;
whatnick 5:81bba9f0f92b 73 // iterate over the string, XOR each byte with the total sum:
whatnick 5:81bba9f0f92b 74 for (int c = 0; c < checkLen; c++) {
whatnick 5:81bba9f0f92b 75 check = char(check ^ theseChars[c]);
whatnick 5:81bba9f0f92b 76 }
whatnick 5:81bba9f0f92b 77 // return the result
whatnick 5:81bba9f0f92b 78 return check;
whatnick 5:81bba9f0f92b 79 }
whatnick 5:81bba9f0f92b 80
whatnick 5:81bba9f0f92b 81
onehorse 0:39935bb3c1a1 82 int main()
onehorse 0:39935bb3c1a1 83 {
whatnick 1:9de6ac4b381d 84
whatnick 1:9de6ac4b381d 85 //Set up I2C
whatnick 1:9de6ac4b381d 86 i2c.frequency(400000); // use fast (400 kHz) I2C
whatnick 1:9de6ac4b381d 87
whatnick 2:f1912528eeaf 88 //Set up GPS
whatnick 2:f1912528eeaf 89 Adafruit_GPS myGPS(&gps);
whatnick 2:f1912528eeaf 90 char c; //when read via Adafruit_GPS::read(), the class returns single character stored here
whatnick 1:9de6ac4b381d 91
whatnick 2:f1912528eeaf 92 LOG("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock);
onehorse 0:39935bb3c1a1 93
whatnick 1:9de6ac4b381d 94 t.start();
whatnick 1:9de6ac4b381d 95
whatnick 2:f1912528eeaf 96 myGPS.begin(9600);
whatnick 5:81bba9f0f92b 97 //Turn off all sentences except GGA and RMC
whatnick 5:81bba9f0f92b 98 //For MTK GPS
whatnick 5:81bba9f0f92b 99 myGPS.sendCommand(PMTK_SET_NMEA_OUTPUT_RMCGGA);
whatnick 5:81bba9f0f92b 100
whatnick 5:81bba9f0f92b 101 //FOR UBLOX GPS
whatnick 5:81bba9f0f92b 102 myGPS.sendCommand(UBX_DISABLE_ZDA);
whatnick 5:81bba9f0f92b 103 myGPS.sendCommand(UBX_DISABLE_GLL);
whatnick 5:81bba9f0f92b 104 myGPS.sendCommand(UBX_DISABLE_VTG);
whatnick 5:81bba9f0f92b 105 myGPS.sendCommand(UBX_DISABLE_GSV);
whatnick 5:81bba9f0f92b 106 myGPS.sendCommand(UBX_DISABLE_GSA);
whatnick 5:81bba9f0f92b 107
whatnick 4:256505da4487 108 wait(1);
whatnick 5:81bba9f0f92b 109 //Set Serial I2C Baudrate
whatnick 2:f1912528eeaf 110 serial_i2c.baud(4800);
whatnick 5:81bba9f0f92b 111 wait(1);
whatnick 5:81bba9f0f92b 112
whatnick 5:81bba9f0f92b 113 //Set output pins for trigggering camera
whatnick 5:81bba9f0f92b 114 serial_i2c.ioSetDirection(0x3);
whatnick 5:81bba9f0f92b 115
whatnick 5:81bba9f0f92b 116 //Set BLE Baud rate
whatnick 5:81bba9f0f92b 117 //serial_i2c.printf("AT+BAUD6");
whatnick 5:81bba9f0f92b 118
whatnick 1:9de6ac4b381d 119 oled.fillDisplay(0xAA);
whatnick 1:9de6ac4b381d 120 oled.setDisplayOff();
onehorse 0:39935bb3c1a1 121 wait(1);
whatnick 1:9de6ac4b381d 122 oled.setDisplayOn();
whatnick 1:9de6ac4b381d 123
whatnick 1:9de6ac4b381d 124 oled.clearDisplay();
whatnick 1:9de6ac4b381d 125 oled.setDisplayInverse();
whatnick 1:9de6ac4b381d 126 wait(0.5);
whatnick 1:9de6ac4b381d 127 oled.setDisplayNormal();
whatnick 1:9de6ac4b381d 128
whatnick 1:9de6ac4b381d 129 oled.writeBitmap((uint8_t*) mbed_logo);
whatnick 1:9de6ac4b381d 130
whatnick 2:f1912528eeaf 131 LOG("OLED test done\r\n");
whatnick 1:9de6ac4b381d 132 wait(10);
whatnick 1:9de6ac4b381d 133 oled.clearDisplay();
whatnick 1:9de6ac4b381d 134
whatnick 2:f1912528eeaf 135 oled.writeString(0, 0, "##AeroAHRS##");
whatnick 1:9de6ac4b381d 136 // Read the WHO_AM_I register, this is a good test of communication
whatnick 1:9de6ac4b381d 137 uint8_t whoami = MPU9150.readByte(MPU9150_ADDRESS, WHO_AM_I_MPU9150); // Read WHO_AM_I register for MPU-9250
whatnick 2:f1912528eeaf 138 LOG("I AM 0x%x\n\r", whoami);
whatnick 2:f1912528eeaf 139 LOG("I SHOULD BE 0x68\n\r");
whatnick 1:9de6ac4b381d 140
whatnick 1:9de6ac4b381d 141 if (whoami == 0x68) { // WHO_AM_I should be 0x68
whatnick 2:f1912528eeaf 142 LOG("MPU9150 WHO_AM_I is 0x%x\n\r", whoami);
whatnick 2:f1912528eeaf 143 LOG("MPU9150 is online...\n\r");
whatnick 1:9de6ac4b381d 144 //lcd.clear();
whatnick 1:9de6ac4b381d 145 //lcd.printString("MPU9150 is", 0, 0);
whatnick 1:9de6ac4b381d 146 //sprintf(buffer, "0x%x", whoami);
whatnick 1:9de6ac4b381d 147 //lcd.printString(buffer, 0, 1);
whatnick 1:9de6ac4b381d 148 //lcd.printString("shoud be 0x68", 0, 2);
whatnick 1:9de6ac4b381d 149 wait(1);
whatnick 1:9de6ac4b381d 150
whatnick 1:9de6ac4b381d 151 MPU9150.MPU9150SelfTest(SelfTest);
whatnick 2:f1912528eeaf 152 LOG("x-axis self test: acceleration trim within %f % of factory value\n\r", SelfTest[0]);
whatnick 2:f1912528eeaf 153 LOG("y-axis self test: acceleration trim within %f % of factory value\n\r", SelfTest[1]);
whatnick 2:f1912528eeaf 154 LOG("z-axis self test: acceleration trim within %f % of factory value\n\r", SelfTest[2]);
whatnick 2:f1912528eeaf 155 LOG("x-axis self test: gyration trim within %f % of factory value\n\r", SelfTest[3]);
whatnick 2:f1912528eeaf 156 LOG("y-axis self test: gyration trim within %f % of factory value\n\r", SelfTest[4]);
whatnick 2:f1912528eeaf 157 LOG("z-axis self test: gyration trim within %f % of factory value\n\r", SelfTest[5]);
whatnick 1:9de6ac4b381d 158 wait(1);
whatnick 1:9de6ac4b381d 159 MPU9150.resetMPU9150(); // Reset registers to default in preparation for device calibration
whatnick 1:9de6ac4b381d 160 MPU9150.calibrateMPU9150(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers
whatnick 2:f1912528eeaf 161 LOG("x gyro bias = %f\n\r", gyroBias[0]);
whatnick 2:f1912528eeaf 162 LOG("y gyro bias = %f\n\r", gyroBias[1]);
whatnick 2:f1912528eeaf 163 LOG("z gyro bias = %f\n\r", gyroBias[2]);
whatnick 2:f1912528eeaf 164 LOG("x accel bias = %f\n\r", accelBias[0]);
whatnick 2:f1912528eeaf 165 LOG("y accel bias = %f\n\r", accelBias[1]);
whatnick 2:f1912528eeaf 166 LOG("z accel bias = %f\n\r", accelBias[2]);
whatnick 1:9de6ac4b381d 167 wait(1);
whatnick 1:9de6ac4b381d 168 MPU9150.initMPU9150();
whatnick 2:f1912528eeaf 169 LOG("MPU9150 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature
whatnick 1:9de6ac4b381d 170 MPU9150.initAK8975A(magCalibration);
whatnick 2:f1912528eeaf 171 LOG("AK8975 initialized for active data mode....\n\r"); // Initialize device for active mode read of magnetometer
whatnick 1:9de6ac4b381d 172 } else {
whatnick 2:f1912528eeaf 173 LOG("Could not connect to MPU9150: \n\r");
whatnick 2:f1912528eeaf 174 LOG("%#x \n", whoami);
whatnick 1:9de6ac4b381d 175
whatnick 1:9de6ac4b381d 176 //lcd.clear();
whatnick 1:9de6ac4b381d 177 //lcd.printString("MPU9150", 0, 0);
whatnick 1:9de6ac4b381d 178 //lcd.printString("no connection", 0, 1);
whatnick 1:9de6ac4b381d 179 sprintf(buffer, "WHO_AM_I 0x%x", whoami);
whatnick 1:9de6ac4b381d 180 //lcd.printString(buffer, 0, 2);
whatnick 1:9de6ac4b381d 181
whatnick 1:9de6ac4b381d 182 while(1) ; // Loop forever if communication doesn't happen
onehorse 0:39935bb3c1a1 183 }
onehorse 0:39935bb3c1a1 184
onehorse 0:39935bb3c1a1 185 uint8_t MagRate = 10; // set magnetometer read rate in Hz; 10 to 100 (max) Hz are reasonable values
onehorse 0:39935bb3c1a1 186 MPU9150.getAres(); // Get accelerometer sensitivity
onehorse 0:39935bb3c1a1 187 MPU9150.getGres(); // Get gyro sensitivity
onehorse 0:39935bb3c1a1 188 mRes = 10.*1229./4096.; // Conversion from 1229 microTesla full scale (4096) to 12.29 Gauss full scale
onehorse 0:39935bb3c1a1 189 // So far, magnetometer bias is calculated and subtracted here manually, should construct an algorithm to do it automatically
onehorse 0:39935bb3c1a1 190 // like the gyro and accelerometer biases
onehorse 0:39935bb3c1a1 191 magbias[0] = -5.; // User environmental x-axis correction in milliGauss
onehorse 0:39935bb3c1a1 192 magbias[1] = -95.; // User environmental y-axis correction in milliGauss
onehorse 0:39935bb3c1a1 193 magbias[2] = -260.; // User environmental z-axis correction in milliGauss
whatnick 1:9de6ac4b381d 194
whatnick 2:f1912528eeaf 195 //Wait for GPS to acquire lock
whatnick 5:81bba9f0f92b 196 oled.writeString(2,0,"GPS Simul ");
whatnick 2:f1912528eeaf 197 while(!myGPS.fix) {
whatnick 2:f1912528eeaf 198 c = myGPS.read(); //queries the GPS
whatnick 2:f1912528eeaf 199 if (c) {
whatnick 2:f1912528eeaf 200 LOG("%c", c); //this line will echo the GPS data if not paused
whatnick 2:f1912528eeaf 201 }
whatnick 2:f1912528eeaf 202
whatnick 2:f1912528eeaf 203 //check if we recieved a new message from GPS, if so, attempt to parse it,
whatnick 2:f1912528eeaf 204 if ( myGPS.newNMEAreceived() ) {
whatnick 2:f1912528eeaf 205 if ( !myGPS.parse(myGPS.lastNMEA()) ) {
whatnick 2:f1912528eeaf 206 continue;
whatnick 2:f1912528eeaf 207 }
whatnick 2:f1912528eeaf 208 }
whatnick 5:81bba9f0f92b 209 /*
whatnick 5:81bba9f0f92b 210 Now = t.read_us();
whatnick 5:81bba9f0f92b 211 deltat = (float)((Now - lastUpdate)/1000000.0f);
whatnick 5:81bba9f0f92b 212
whatnick 5:81bba9f0f92b 213 bool up = false;
whatnick 5:81bba9f0f92b 214 if(deltat > 0.5f)
whatnick 5:81bba9f0f92b 215 {
whatnick 5:81bba9f0f92b 216 bmp.update();
whatnick 5:81bba9f0f92b 217 float temp = bmp.get_temperature();
whatnick 5:81bba9f0f92b 218 float pres = bmp.get_pressure();
whatnick 5:81bba9f0f92b 219 float baroAlt = (float)44330 * (1 - pow((float)(pres/SEA_PRES), 0.190295f));
whatnick 5:81bba9f0f92b 220
whatnick 5:81bba9f0f92b 221 sprintf(buffer,"ALT:%5.2f",baroAlt);
whatnick 5:81bba9f0f92b 222 oled.writeString(4,0,buffer);
whatnick 5:81bba9f0f92b 223 sprintf(buffer,"TMP:%5.2f",temp);
whatnick 5:81bba9f0f92b 224 oled.writeString(5,0,buffer);
whatnick 5:81bba9f0f92b 225 sprintf(buffer,"PRS:%5.2f",pres);
whatnick 5:81bba9f0f92b 226 oled.writeString(6,0,buffer);
whatnick 5:81bba9f0f92b 227
whatnick 5:81bba9f0f92b 228 serial_i2c.printf("$GPRMC,000002.000,A,3456.9076,S,13831.2800,E,0.00,65.44,240215,,,D*49\r\n");
whatnick 5:81bba9f0f92b 229 serial_i2c.printf("$PTNTHPR,105.0,N,-21.4,N,0.9,N,A*79\r\n");
whatnick 5:81bba9f0f92b 230 wait(0.1);
whatnick 5:81bba9f0f92b 231 //serial_i2c.printf("$GPVTG,65.44,T,,M,0.00,N,0.00,K,D*0B");
whatnick 5:81bba9f0f92b 232 sprintf(buffer+1,"GPGGA,000002.000,3456.9076,S,13831.2800,E,2,07,0.94,%5.2f,M,-0.5,M,,",baroAlt);
whatnick 5:81bba9f0f92b 233 int checkS = checkSum(buffer+1,strlen(buffer+1));
whatnick 5:81bba9f0f92b 234 buffer[0] = '$';
whatnick 5:81bba9f0f92b 235 serial_i2c.printf(buffer);
whatnick 5:81bba9f0f92b 236 serial_i2c.printf("*%02X\r\n",checkS);
whatnick 5:81bba9f0f92b 237 wait(0.1);
whatnick 5:81bba9f0f92b 238 serial_i2c.printf("$GPGSA,A,3,13,15,24,06,12,02,28,,,,,,1.32,0.94,0.92*09\r\n");
whatnick 5:81bba9f0f92b 239 serial_i2c.printf("$GPGLL,3456.9076,S,13831.2800,E,000002.000,A,D*4D\r\n");
whatnick 5:81bba9f0f92b 240 serial_i2c.printf("$NKGCS,WGS 84*11\r\n");
whatnick 5:81bba9f0f92b 241
whatnick 5:81bba9f0f92b 242 if(up)
whatnick 5:81bba9f0f92b 243 {
whatnick 5:81bba9f0f92b 244 serial_i2c.ioSetState(0x0);
whatnick 5:81bba9f0f92b 245 up = false;
whatnick 5:81bba9f0f92b 246 }
whatnick 5:81bba9f0f92b 247 else
whatnick 5:81bba9f0f92b 248 {
whatnick 5:81bba9f0f92b 249 serial_i2c.ioSetState(0x3);
whatnick 5:81bba9f0f92b 250 up = true;
whatnick 5:81bba9f0f92b 251 }
whatnick 5:81bba9f0f92b 252 lastUpdate = Now;
whatnick 5:81bba9f0f92b 253 }
whatnick 5:81bba9f0f92b 254 */
whatnick 2:f1912528eeaf 255 }
whatnick 2:f1912528eeaf 256
whatnick 1:9de6ac4b381d 257 mkdir("/sd/logdir", 0777);
whatnick 2:f1912528eeaf 258 sprintf(buffer,"/sd/logdir/%d%d20%d_%d%d%d.txt",myGPS.day, myGPS.month, myGPS.year,
whatnick 2:f1912528eeaf 259 myGPS.hour, myGPS.minute, myGPS.seconds);
whatnick 2:f1912528eeaf 260 FILE *fp = fopen(buffer, "w");
whatnick 1:9de6ac4b381d 261 if(fp == NULL) {
whatnick 1:9de6ac4b381d 262 LOG("Could not open file for write\n");
whatnick 1:9de6ac4b381d 263 oled.writeString(7,0,"SD Fail");
whatnick 2:f1912528eeaf 264 } else {
whatnick 2:f1912528eeaf 265 oled.writeString(7,0,"SD OKAY");
whatnick 1:9de6ac4b381d 266 }
onehorse 0:39935bb3c1a1 267
whatnick 1:9de6ac4b381d 268 while(1) {
whatnick 5:81bba9f0f92b 269 c = myGPS.read(); //queries the GPS
whatnick 5:81bba9f0f92b 270 if (c) {
whatnick 5:81bba9f0f92b 271 LOG("%c", c); //this line will echo the GPS data if not paused
whatnick 5:81bba9f0f92b 272 //serial_i2c.putc(c);
whatnick 5:81bba9f0f92b 273 //serial_i2c.printf("$GPGGA,154850.00,3452.12190,S,13836.65170,E,1,04,1.64,123.5,M,0.0,M,,*7F\r\n");
whatnick 5:81bba9f0f92b 274 //$GPGGA,160202.00,3452.14414,S,13836.63059,E,1,04,2.60,45.4,M,-3.4,M,,*6B
whatnick 5:81bba9f0f92b 275 //serial_i2c.printf("$GPRMC,154850.00,A,3452.12190,S,13836.65170,E,0.510,,110215,,,A*63\r\n");
whatnick 5:81bba9f0f92b 276 //$GPRMC,160203.00,A,3452.14414,S,13836.63079,E,0.332,,110215,,,A*6F
whatnick 5:81bba9f0f92b 277 }
whatnick 5:81bba9f0f92b 278
whatnick 1:9de6ac4b381d 279 // If intPin goes high, all data registers have new data
whatnick 1:9de6ac4b381d 280 if(MPU9150.readByte(MPU9150_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt
whatnick 1:9de6ac4b381d 281
whatnick 1:9de6ac4b381d 282 MPU9150.readAccelData(accelCount); // Read the x/y/z adc values
whatnick 1:9de6ac4b381d 283 // Now we'll calculate the accleration value into actual g's
whatnick 1:9de6ac4b381d 284 ax = (float)accelCount[0]*aRes; // - accelBias[0]; // get actual g value, this depends on scale being set
whatnick 1:9de6ac4b381d 285 ay = (float)accelCount[1]*aRes; // - accelBias[1];
whatnick 1:9de6ac4b381d 286 az = (float)accelCount[2]*aRes; // - accelBias[2];
onehorse 0:39935bb3c1a1 287
whatnick 1:9de6ac4b381d 288 MPU9150.readGyroData(gyroCount); // Read the x/y/z adc values
whatnick 1:9de6ac4b381d 289 // Calculate the gyro value into actual degrees per second
whatnick 1:9de6ac4b381d 290 gx = (float)gyroCount[0]*gRes; // - gyroBias[0]; // get actual gyro value, this depends on scale being set
whatnick 1:9de6ac4b381d 291 gy = (float)gyroCount[1]*gRes; // - gyroBias[1];
whatnick 1:9de6ac4b381d 292 gz = (float)gyroCount[2]*gRes; // - gyroBias[2];
whatnick 1:9de6ac4b381d 293
whatnick 1:9de6ac4b381d 294 mcount++;
whatnick 1:9de6ac4b381d 295 if (mcount > 200/MagRate) { // this is a poor man's way of setting the magnetometer read rate (see below)
whatnick 1:9de6ac4b381d 296 MPU9150.readMagData(magCount); // Read the x/y/z adc values
whatnick 1:9de6ac4b381d 297 // Calculate the magnetometer values in milliGauss
whatnick 1:9de6ac4b381d 298 // Include factory calibration per data sheet and user environmental corrections
whatnick 1:9de6ac4b381d 299 mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0]; // get actual magnetometer value, this depends on scale being set
whatnick 1:9de6ac4b381d 300 my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1];
whatnick 1:9de6ac4b381d 301 mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2];
whatnick 1:9de6ac4b381d 302 mcount = 0;
whatnick 1:9de6ac4b381d 303 }
whatnick 1:9de6ac4b381d 304 }
whatnick 1:9de6ac4b381d 305
whatnick 2:f1912528eeaf 306 //Handle GPS data
whatnick 2:f1912528eeaf 307 {
whatnick 2:f1912528eeaf 308 c = myGPS.read(); //queries the GPS
whatnick 2:f1912528eeaf 309 if (c) {
whatnick 2:f1912528eeaf 310 LOG("%c", c); //this line will echo the GPS data if not paused
whatnick 5:81bba9f0f92b 311 //serial_i2c.putc(c);
whatnick 2:f1912528eeaf 312 }
whatnick 2:f1912528eeaf 313
whatnick 2:f1912528eeaf 314 //check if we recieved a new message from GPS, if so, attempt to parse it,
whatnick 2:f1912528eeaf 315 if ( myGPS.newNMEAreceived() ) {
whatnick 2:f1912528eeaf 316 if ( !myGPS.parse(myGPS.lastNMEA()) ) {
whatnick 2:f1912528eeaf 317 continue;
whatnick 2:f1912528eeaf 318 }
whatnick 5:81bba9f0f92b 319
whatnick 2:f1912528eeaf 320 else
whatnick 2:f1912528eeaf 321 {
whatnick 2:f1912528eeaf 322 serial_i2c.printf(myGPS.lastNMEA());
whatnick 5:81bba9f0f92b 323 serial_i2c.printf("\n\r");
whatnick 5:81bba9f0f92b 324 if(myGPS.fix && fp!=NULL) {
whatnick 5:81bba9f0f92b 325 fprintf(fp,myGPS.lastNMEA());
whatnick 5:81bba9f0f92b 326 fprintf(fp,"\r\n");
whatnick 5:81bba9f0f92b 327 }
whatnick 2:f1912528eeaf 328 }
whatnick 5:81bba9f0f92b 329
whatnick 2:f1912528eeaf 330 }
whatnick 2:f1912528eeaf 331 }
whatnick 2:f1912528eeaf 332
whatnick 1:9de6ac4b381d 333 Now = t.read_us();
whatnick 1:9de6ac4b381d 334 deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update
whatnick 1:9de6ac4b381d 335 lastUpdate = Now;
whatnick 1:9de6ac4b381d 336
whatnick 1:9de6ac4b381d 337 sum += deltat;
whatnick 1:9de6ac4b381d 338 sumCount++;
whatnick 1:9de6ac4b381d 339
onehorse 0:39935bb3c1a1 340 // if(lastUpdate - firstUpdate > 10000000.0f) {
onehorse 0:39935bb3c1a1 341 // beta = 0.04; // decrease filter gain after stabilized
onehorse 0:39935bb3c1a1 342 // zeta = 0.015; // increasey bias drift gain after stabilized
whatnick 1:9de6ac4b381d 343 // }
whatnick 1:9de6ac4b381d 344
whatnick 1:9de6ac4b381d 345 // Pass gyro rate as rad/s
whatnick 1:9de6ac4b381d 346 MPU9150.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
whatnick 1:9de6ac4b381d 347 // MPU9150.MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
whatnick 1:9de6ac4b381d 348
whatnick 1:9de6ac4b381d 349 // Serial print and/or display at 0.5 s rate independent of data rates
whatnick 1:9de6ac4b381d 350 delt_t = t.read_ms() - count;
whatnick 1:9de6ac4b381d 351 if (delt_t > 500) { // update LCD once per half-second independent of read rate
whatnick 1:9de6ac4b381d 352
whatnick 2:f1912528eeaf 353 LOG("ax = %f", 1000*ax);
whatnick 2:f1912528eeaf 354 LOG(" ay = %f", 1000*ay);
whatnick 2:f1912528eeaf 355 LOG(" az = %f mg\n\r", 1000*az);
onehorse 0:39935bb3c1a1 356
whatnick 2:f1912528eeaf 357 LOG("gx = %f", gx);
whatnick 2:f1912528eeaf 358 LOG(" gy = %f", gy);
whatnick 2:f1912528eeaf 359 LOG(" gz = %f deg/s\n\r", gz);
whatnick 1:9de6ac4b381d 360
whatnick 2:f1912528eeaf 361 LOG("gx = %f", mx);
whatnick 2:f1912528eeaf 362 LOG(" gy = %f", my);
whatnick 2:f1912528eeaf 363 LOG(" gz = %f mG\n\r", mz);
onehorse 0:39935bb3c1a1 364
whatnick 1:9de6ac4b381d 365 tempCount = MPU9150.readTempData(); // Read the adc values
whatnick 1:9de6ac4b381d 366 temperature = ((float) tempCount) / 340.0f + 36.53f; // Temperature in degrees Centigrade
whatnick 2:f1912528eeaf 367 LOG(" temperature = %f C\n\r", temperature);
onehorse 0:39935bb3c1a1 368
whatnick 2:f1912528eeaf 369 LOG("q0 = %f\n\r", q[0]);
whatnick 2:f1912528eeaf 370 LOG("q1 = %f\n\r", q[1]);
whatnick 2:f1912528eeaf 371 LOG("q2 = %f\n\r", q[2]);
whatnick 2:f1912528eeaf 372 LOG("q3 = %f\n\r", q[3]);
whatnick 2:f1912528eeaf 373
whatnick 1:9de6ac4b381d 374 // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation.
whatnick 1:9de6ac4b381d 375 // In this coordinate system, the positive z-axis is down toward Earth.
whatnick 1:9de6ac4b381d 376 // 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 377 // 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 378 // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll.
whatnick 1:9de6ac4b381d 379 // These arise from the definition of the homogeneous rotation matrix constructed from quaternions.
whatnick 1:9de6ac4b381d 380 // 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 381 // applied in the correct order which for this configuration is yaw, pitch, and then roll.
whatnick 1:9de6ac4b381d 382 // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links.
whatnick 1:9de6ac4b381d 383 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 384 pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
whatnick 1:9de6ac4b381d 385 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 386 pitch *= 180.0f / PI;
whatnick 1:9de6ac4b381d 387 yaw *= 180.0f / PI;
whatnick 1:9de6ac4b381d 388 yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04
whatnick 1:9de6ac4b381d 389 roll *= 180.0f / PI;
onehorse 0:39935bb3c1a1 390
whatnick 1:9de6ac4b381d 391
whatnick 5:81bba9f0f92b 392 LOG("Yaw, Pitch, Roll: %f %f %f\r\n", yaw, pitch, roll);
whatnick 5:81bba9f0f92b 393 LOG("average rate = %f\r\n", (float) sumCount/sum);
whatnick 2:f1912528eeaf 394
whatnick 2:f1912528eeaf 395 sprintf(buffer, "YPR:%3.0f %3.0f %3.0f", yaw, pitch, roll);
whatnick 1:9de6ac4b381d 396 oled.writeString(1,0,buffer);
whatnick 5:81bba9f0f92b 397 sprintf(buffer+1,"PTNTHPR,%3.1f,N,%3.1f,N,%3.1f,N,A",yaw,pitch,roll);
whatnick 5:81bba9f0f92b 398 int checkS = checkSum(buffer+1,strlen(buffer+1));
whatnick 5:81bba9f0f92b 399 buffer[0] = '$';
whatnick 5:81bba9f0f92b 400 serial_i2c.printf(buffer);
whatnick 5:81bba9f0f92b 401 serial_i2c.printf("*%02X\r\n",checkS);
whatnick 2:f1912528eeaf 402 if(fp != NULL) {
whatnick 5:81bba9f0f92b 403 fprintf(fp,"%s%02X\r\n",buffer,checkS);
whatnick 2:f1912528eeaf 404 if(fflush(fp)==EOF) {
whatnick 2:f1912528eeaf 405 //SD card removed close file pointer
whatnick 2:f1912528eeaf 406 oled.writeString(7,0,"SD Fail");
whatnick 2:f1912528eeaf 407 fp=NULL;
whatnick 2:f1912528eeaf 408 }
whatnick 2:f1912528eeaf 409 }
whatnick 2:f1912528eeaf 410
whatnick 2:f1912528eeaf 411 LOG("Time: %d:%d:%d.%u\n", myGPS.hour, myGPS.minute, myGPS.seconds, myGPS.milliseconds);
whatnick 2:f1912528eeaf 412 LOG("Date: %d/%d/20%d\n", myGPS.day, myGPS.month, myGPS.year);
whatnick 2:f1912528eeaf 413 LOG("Fix: %d\n", (int) myGPS.fix);
whatnick 2:f1912528eeaf 414 LOG("Quality: %d\n", (int) myGPS.fixquality);
whatnick 2:f1912528eeaf 415 if (myGPS.fix) {
whatnick 2:f1912528eeaf 416 LOG("Location: %5.2f%c, %5.2f%c\n", myGPS.latitude, myGPS.lat, myGPS.longitude, myGPS.lon);
whatnick 2:f1912528eeaf 417 LOG("Speed: %5.2f knots\n", myGPS.speed);
whatnick 2:f1912528eeaf 418 LOG("Angle: %5.2f\n", myGPS.angle);
whatnick 2:f1912528eeaf 419 LOG("Altitude: %5.2f\n", myGPS.altitude);
whatnick 2:f1912528eeaf 420 LOG("Satellites: %d\n", myGPS.satellites);
whatnick 2:f1912528eeaf 421 }
whatnick 2:f1912528eeaf 422
whatnick 2:f1912528eeaf 423 if (myGPS.fix) {
whatnick 2:f1912528eeaf 424 sprintf(buffer,"LAT:%5.5f%c",myGPS.latitude,myGPS.lat);
whatnick 2:f1912528eeaf 425 oled.writeString(2,0,buffer);
whatnick 2:f1912528eeaf 426 sprintf(buffer,"LON:%5.5f%c",myGPS.longitude,myGPS.lon);
whatnick 2:f1912528eeaf 427 oled.writeString(3,0,buffer);
whatnick 2:f1912528eeaf 428 sprintf(buffer,"ALT:%5.2f",myGPS.altitude);
whatnick 2:f1912528eeaf 429 oled.writeString(4,0,buffer);
whatnick 2:f1912528eeaf 430 } else {
whatnick 2:f1912528eeaf 431 oled.writeString(2,0," ");
whatnick 2:f1912528eeaf 432 oled.writeString(2,0,"GPS Lost ");
whatnick 2:f1912528eeaf 433 oled.writeString(3,0," ");
whatnick 2:f1912528eeaf 434 oled.writeString(4,0," ");
whatnick 2:f1912528eeaf 435 }
whatnick 2:f1912528eeaf 436 sprintf(buffer,"Time: %d:%d:%d.%u\n", myGPS.hour, myGPS.minute, myGPS.seconds, myGPS.milliseconds);
whatnick 2:f1912528eeaf 437 oled.writeString(5,0,buffer);
whatnick 2:f1912528eeaf 438 sprintf(buffer,"Date: %d/%d/20%d\n", myGPS.day, myGPS.month, myGPS.year);
whatnick 2:f1912528eeaf 439 oled.writeString(6,0,buffer);
whatnick 2:f1912528eeaf 440
whatnick 2:f1912528eeaf 441 if(fp != NULL) {
whatnick 2:f1912528eeaf 442 if(fflush(fp)==EOF) {
whatnick 2:f1912528eeaf 443 //SD card removed close file pointer
whatnick 2:f1912528eeaf 444 oled.writeString(7,0,"SD Fail");
whatnick 2:f1912528eeaf 445 fp=NULL;
whatnick 2:f1912528eeaf 446 }
whatnick 2:f1912528eeaf 447 }
whatnick 2:f1912528eeaf 448
whatnick 2:f1912528eeaf 449 //if FP is null at the end of the loop attempt to open new log with fix
whatnick 2:f1912528eeaf 450 if(fp==NULL && myGPS.fix) {
whatnick 2:f1912528eeaf 451 mkdir("/sd/logdir", 0777);
whatnick 2:f1912528eeaf 452 sprintf(buffer,"/sd/logdir/%d%d20%d_%d%d%d.txt",myGPS.day, myGPS.month, myGPS.year,
whatnick 2:f1912528eeaf 453 myGPS.hour, myGPS.minute, myGPS.seconds);
whatnick 2:f1912528eeaf 454 FILE *fp = fopen(buffer, "w");
whatnick 2:f1912528eeaf 455 if(fp == NULL) {
whatnick 2:f1912528eeaf 456 LOG("Could not open file for write\n");
whatnick 2:f1912528eeaf 457 oled.writeString(7,0,"SD Fail");
whatnick 2:f1912528eeaf 458 } else {
whatnick 2:f1912528eeaf 459 oled.writeString(7,0,"SD OKAY");
whatnick 2:f1912528eeaf 460 }
whatnick 2:f1912528eeaf 461 }
whatnick 1:9de6ac4b381d 462
whatnick 1:9de6ac4b381d 463 myled= !myled;
whatnick 1:9de6ac4b381d 464 count = t.read_ms();
onehorse 0:39935bb3c1a1 465
whatnick 1:9de6ac4b381d 466 if(count > 1<<21) {
whatnick 1:9de6ac4b381d 467 t.start(); // start the timer over again if ~30 minutes has passed
whatnick 1:9de6ac4b381d 468 count = 0;
whatnick 1:9de6ac4b381d 469 deltat= 0;
whatnick 1:9de6ac4b381d 470 lastUpdate = t.read_us();
whatnick 1:9de6ac4b381d 471 }
whatnick 1:9de6ac4b381d 472 sum = 0;
whatnick 1:9de6ac4b381d 473 sumCount = 0;
whatnick 5:81bba9f0f92b 474
whatnick 1:9de6ac4b381d 475 }
onehorse 0:39935bb3c1a1 476 }
whatnick 5:81bba9f0f92b 477 }
whatnick 1:9de6ac4b381d 478