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

Revision:
5:81bba9f0f92b
Parent:
4:256505da4487
Child:
7:37bd00805530
--- a/main.cpp	Sun Dec 28 13:42:56 2014 +0000
+++ b/main.cpp	Mon May 25 02:51:01 2015 +0000
@@ -35,6 +35,7 @@
 #include "SDFileSystem.h"
 #include "MBed_Adafruit_GPS.h"
 #include "SC16IS750.h"
+#include "BMP085.h"
 
 //Use Xadow OLED for display
 SSD1308 oled = SSD1308(i2c, SSD1308_SA0);
@@ -42,11 +43,14 @@
 //Use Serial expander for extra UART
 SC16IS750_I2C serial_i2c(&i2c, SC16IS750_SA5);
 
+//Use BMP085 Temperature,Pressure
+BMP085 bmp(i2c);
+
 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
 
 float sum = 0;
 uint32_t sumCount = 0, mcount = 0;
-char buffer[32];
+char buffer[64];
 
 MPU9150 MPU9150;
 
@@ -64,6 +68,17 @@
 #define LOG(args...)
 #endif
 
+char checkSum(char* theseChars,int checkLen) {
+  char check = 0;
+  // iterate over the string, XOR each byte with the total sum:
+  for (int c = 0; c < checkLen; c++) {
+    check = char(check ^ theseChars[c]);
+  } 
+  // return the result
+  return check;
+}
+
+
 int main()
 {
 
@@ -79,11 +94,28 @@
     t.start();
 
     myGPS.begin(9600);
-    //Set BLE baudrate
-    serial_i2c.baud(9600);
-    serial_i2c.printf("AT+BAUD6");
+    //Turn off all sentences except GGA and RMC
+    //For MTK GPS
+    myGPS.sendCommand(PMTK_SET_NMEA_OUTPUT_RMCGGA);
+    
+    //FOR UBLOX GPS
+    myGPS.sendCommand(UBX_DISABLE_ZDA);
+    myGPS.sendCommand(UBX_DISABLE_GLL);
+    myGPS.sendCommand(UBX_DISABLE_VTG);
+    myGPS.sendCommand(UBX_DISABLE_GSV);
+    myGPS.sendCommand(UBX_DISABLE_GSA);
+    
     wait(1);
+    //Set Serial I2C Baudrate
     serial_i2c.baud(4800);
+    wait(1);
+    
+    //Set output pins for trigggering camera
+    serial_i2c.ioSetDirection(0x3);
+    
+    //Set BLE Baud rate
+    //serial_i2c.printf("AT+BAUD6");
+    
     oled.fillDisplay(0xAA);
     oled.setDisplayOff();
     wait(1);
@@ -161,7 +193,7 @@
     magbias[2] = -260.; // User environmental z-axis correction in milliGauss
 
     //Wait for GPS to acquire lock
-    oled.writeString(2,0,"GPS Init ");
+    oled.writeString(2,0,"GPS Simul ");
     while(!myGPS.fix) {
         c = myGPS.read();   //queries the GPS
         if (c) {
@@ -174,6 +206,52 @@
                 continue;
             }
         }
+        /*
+        Now = t.read_us();
+        deltat = (float)((Now - lastUpdate)/1000000.0f);
+        
+        bool up = false;
+        if(deltat > 0.5f)
+        {
+            bmp.update();
+            float temp = bmp.get_temperature();
+            float pres = bmp.get_pressure();
+            float baroAlt = (float)44330 * (1 - pow((float)(pres/SEA_PRES), 0.190295f));
+            
+            sprintf(buffer,"ALT:%5.2f",baroAlt);
+            oled.writeString(4,0,buffer);
+            sprintf(buffer,"TMP:%5.2f",temp);
+            oled.writeString(5,0,buffer);
+            sprintf(buffer,"PRS:%5.2f",pres);
+            oled.writeString(6,0,buffer);
+            
+            serial_i2c.printf("$GPRMC,000002.000,A,3456.9076,S,13831.2800,E,0.00,65.44,240215,,,D*49\r\n");
+            serial_i2c.printf("$PTNTHPR,105.0,N,-21.4,N,0.9,N,A*79\r\n");
+            wait(0.1);
+            //serial_i2c.printf("$GPVTG,65.44,T,,M,0.00,N,0.00,K,D*0B");
+            sprintf(buffer+1,"GPGGA,000002.000,3456.9076,S,13831.2800,E,2,07,0.94,%5.2f,M,-0.5,M,,",baroAlt);
+            int checkS = checkSum(buffer+1,strlen(buffer+1));
+            buffer[0] = '$';
+            serial_i2c.printf(buffer);
+            serial_i2c.printf("*%02X\r\n",checkS);
+            wait(0.1);
+            serial_i2c.printf("$GPGSA,A,3,13,15,24,06,12,02,28,,,,,,1.32,0.94,0.92*09\r\n");
+            serial_i2c.printf("$GPGLL,3456.9076,S,13831.2800,E,000002.000,A,D*4D\r\n");
+            serial_i2c.printf("$NKGCS,WGS 84*11\r\n");
+            
+            if(up)
+            {
+                serial_i2c.ioSetState(0x0);
+                up = false;
+            }
+            else
+            {
+                serial_i2c.ioSetState(0x3);
+                up = true;
+            }
+            lastUpdate = Now;
+        }
+        */
     }
 
     mkdir("/sd/logdir", 0777);
@@ -188,7 +266,16 @@
     }
 
     while(1) {
-
+        c = myGPS.read();   //queries the GPS
+        if (c) {
+            LOG("%c", c);    //this line will echo the GPS data if not paused
+            //serial_i2c.putc(c);
+            //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");
+            //$GPGGA,160202.00,3452.14414,S,13836.63059,E,1,04,2.60,45.4,M,-3.4,M,,*6B
+            //serial_i2c.printf("$GPRMC,154850.00,A,3452.12190,S,13836.65170,E,0.510,,110215,,,A*63\r\n");
+            //$GPRMC,160203.00,A,3452.14414,S,13836.63079,E,0.332,,110215,,,A*6F
+        }
+        
         // If intPin goes high, all data registers have new data
         if(MPU9150.readByte(MPU9150_ADDRESS, INT_STATUS) & 0x01) {  // On interrupt, check if data ready interrupt
 
@@ -221,6 +308,7 @@
             c = myGPS.read();   //queries the GPS
             if (c) {
                 LOG("%c", c);    //this line will echo the GPS data if not paused
+                //serial_i2c.putc(c);
             }
 
             //check if we recieved a new message from GPS, if so, attempt to parse it,
@@ -228,10 +316,17 @@
                 if ( !myGPS.parse(myGPS.lastNMEA()) ) {
                     continue;
                 }
+                
                 else
                 {
                     serial_i2c.printf(myGPS.lastNMEA());
+                    serial_i2c.printf("\n\r");
+                    if(myGPS.fix && fp!=NULL) {
+                        fprintf(fp,myGPS.lastNMEA());
+                        fprintf(fp,"\r\n");
+                    }
                 }
+                
             }
         }
 
@@ -294,13 +389,18 @@
             roll  *= 180.0f / PI;
 
 
-            LOG("Yaw, Pitch, Roll: %f %f %f\n\r", yaw, pitch, roll);
-            LOG("average rate = %f\n\r", (float) sumCount/sum);
+            LOG("Yaw, Pitch, Roll: %f %f %f\r\n", yaw, pitch, roll);
+            LOG("average rate = %f\r\n", (float) sumCount/sum);
 
             sprintf(buffer, "YPR:%3.0f %3.0f %3.0f", yaw, pitch, roll);
             oled.writeString(1,0,buffer);
+            sprintf(buffer+1,"PTNTHPR,%3.1f,N,%3.1f,N,%3.1f,N,A",yaw,pitch,roll);
+            int checkS = checkSum(buffer+1,strlen(buffer+1));
+            buffer[0] = '$';
+            serial_i2c.printf(buffer);
+            serial_i2c.printf("*%02X\r\n",checkS);
             if(fp != NULL) {
-                fprintf(fp,"YPR: %f %f %f\n", yaw, pitch, roll);
+                fprintf(fp,"%s%02X\r\n",buffer,checkS);
                 if(fflush(fp)==EOF) {
                     //SD card removed close file pointer
                     oled.writeString(7,0,"SD Fail");
@@ -338,12 +438,7 @@
             sprintf(buffer,"Date: %d/%d/20%d\n", myGPS.day, myGPS.month, myGPS.year);
             oled.writeString(6,0,buffer);
 
-            if(myGPS.fix && fp!=NULL) {
-                fprintf(fp,"LLA: %5.6f%c, %5.6f%c, %5.2f\n", myGPS.latitude, myGPS.lat, myGPS.longitude, myGPS.lon,myGPS.altitude);
-            }
-
             if(fp != NULL) {
-                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);
                 if(fflush(fp)==EOF) {
                     //SD card removed close file pointer
                     oled.writeString(7,0,"SD Fail");
@@ -376,7 +471,8 @@
             }
             sum = 0;
             sumCount = 0;
+            
         }
     }
+}
 
-}
\ No newline at end of file