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
main.cpp
00001 /* MPU9150 Basic Example Code 00002 by: Kris Winer 00003 date: April 1, 2014 00004 license: Beerware - Use this code however you'd like. If you 00005 find it useful you can buy me a beer some time. 00006 00007 Demonstrate basic MPU-9150 functionality including parameterizing the register addresses, initializing the sensor, 00008 getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to 00009 allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and 00010 Mahony filter algorithms. Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1. 00011 00012 SDA and SCL should have external pull-up resistors (to 3.3V). 00013 10k resistors are on the EMSENSR-9250 breakout board. 00014 00015 Hardware setup: 00016 MPU9150 Breakout --------- Arduino 00017 VDD ---------------------- 3.3V 00018 VDDI --------------------- 3.3V 00019 SDA ----------------------- A4 00020 SCL ----------------------- A5 00021 GND ---------------------- GND 00022 00023 Note: The MPU9150 is an I2C sensor and uses the Arduino Wire library. 00024 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. 00025 We have disabled the internal pull-ups used by the Wire library in the Wire.h/twi.c utility file. 00026 We are also using the 400 kHz fast I2C mode by setting the TWI_FREQ to 400000L /twi.h utility file. 00027 */ 00028 00029 //#include "ST_F401_84MHZ.h" 00030 //F401_init84 myinit(0); 00031 #include "mbed.h" 00032 #include "mbed_logo.h" 00033 #include "MPU9150.h" 00034 #include "SSD1308.h" 00035 #include "SDFileSystem.h" 00036 #include "MBed_Adafruit_GPS.h" 00037 #include "SC16IS750.h" 00038 #include "BMP085.h" 00039 00040 //Use Xadow OLED for display 00041 SSD1308 oled = SSD1308(i2c, SSD1308_SA0); 00042 00043 //Use Serial expander for extra UART 00044 SPI spi(P0_9,P0_8,P0_10); //MOSI, MISO, SCK 00045 DigitalOut CS(P0_15); //CS 00046 SC16IS752_SPI serial_spi_nikon(&spi,P0_15,NC,SC16IS750::Channel_B); 00047 SC16IS752_SPI serial_spi_ble(&spi,P0_15,NC,SC16IS750::Channel_A); 00048 00049 //Use BMP085 Temperature,Pressure 00050 BMP085 bmp(i2c); 00051 00052 SDFileSystem sd(P0_21, P0_22, P1_15, P1_19, "sd", P0_20, SDFileSystem::SWITCH_POS_NC); // Pin-out on Xadow SD board attached to 1st SPI 00053 00054 float sum = 0; 00055 uint32_t sumCount = 0, mcount = 0; 00056 char buffer[64]; 00057 00058 MPU9150 MPU9150; 00059 00060 Timer t; 00061 00062 Serial gps(P0_19,P0_18); 00063 00064 //#define DEBUG 00065 00066 #ifdef DEBUG 00067 #include "USBSerial.h" // To use USB virtual serial, a driver is needed, check http://mbed.org/handbook/USBSerial 00068 #define LOG(args...) pc.printf(args) 00069 #else 00070 #define LOG(args...) 00071 #endif 00072 00073 char checkSum(char* theseChars,int checkLen) { 00074 char check = 0; 00075 // iterate over the string, XOR each byte with the total sum: 00076 for (int c = 0; c < checkLen; c++) { 00077 check = char(check ^ theseChars[c]); 00078 } 00079 // return the result 00080 return check; 00081 } 00082 00083 00084 int main() 00085 { 00086 00087 //Set up I2C 00088 i2c.frequency(400000); // use fast (400 kHz) I2C 00089 00090 //Set up SPI 00091 spi.format(8, 0);; 00092 // spi.frequency(100000); 00093 // spi.frequency(500000); 00094 spi.frequency(1000000); 00095 00096 //Set up GPS 00097 Adafruit_GPS myGPS(&gps); 00098 char c; //when read via Adafruit_GPS::read(), the class returns single character stored here 00099 00100 LOG("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock); 00101 00102 t.start(); 00103 00104 myGPS.begin(9600); 00105 //Turn off all sentences except GGA and RMC 00106 //For MTK GPS 00107 myGPS.sendCommand(PMTK_SET_NMEA_OUTPUT_RMCGGA); 00108 00109 //FOR UBLOX GPS 00110 myGPS.sendCommand(UBX_DISABLE_ZDA); 00111 myGPS.sendCommand(UBX_DISABLE_GLL); 00112 myGPS.sendCommand(UBX_DISABLE_VTG); 00113 myGPS.sendCommand(UBX_DISABLE_GSV); 00114 myGPS.sendCommand(UBX_DISABLE_GSA); 00115 00116 wait(1); 00117 //Set Serial I2C Baudrate for Nikon 00118 serial_spi_nikon.baud(4800); 00119 wait(1); 00120 00121 //Set Serial SPI Baudrate for BLE 00122 serial_spi_ble.baud(2400); 00123 wait(1); 00124 00125 //Set BLE Baud rate 00126 //serial_spi_ble.printf("AT+BAUD2"); 00127 //wait(1); 00128 //serial_spi_ble.baud(19200); 00129 //wait(1); 00130 00131 //Set output pins for trigggering camera 00132 serial_spi_nikon.ioSetDirection(0xFF); // All outputs 00133 serial_spi_nikon.ioSetState(0xFF); // All On 00134 00135 00136 00137 oled.fillDisplay(0xAA); 00138 oled.setDisplayOff(); 00139 wait(1); 00140 oled.setDisplayOn(); 00141 00142 oled.clearDisplay(); 00143 oled.setDisplayInverse(); 00144 wait(0.5); 00145 oled.setDisplayNormal(); 00146 00147 oled.writeBitmap((uint8_t*) mbed_logo); 00148 00149 LOG("OLED test done\r\n"); 00150 wait(10); 00151 oled.clearDisplay(); 00152 00153 oled.writeString(0, 0, "##AeroGPS-AHRS##"); 00154 // Read the WHO_AM_I register, this is a good test of communication 00155 uint8_t whoami = MPU9150.readByte(MPU9150_ADDRESS, WHO_AM_I_MPU9150); // Read WHO_AM_I register for MPU-9250 00156 LOG("I AM 0x%x\n\r", whoami); 00157 LOG("I SHOULD BE 0x68\n\r"); 00158 00159 if (whoami == 0x68) { // WHO_AM_I should be 0x68 00160 LOG("MPU9150 WHO_AM_I is 0x%x\n\r", whoami); 00161 LOG("MPU9150 is online...\n\r"); 00162 //lcd.clear(); 00163 //lcd.printString("MPU9150 is", 0, 0); 00164 //sprintf(buffer, "0x%x", whoami); 00165 //lcd.printString(buffer, 0, 1); 00166 //lcd.printString("shoud be 0x68", 0, 2); 00167 wait(1); 00168 00169 MPU9150.MPU9150SelfTest(SelfTest); 00170 LOG("x-axis self test: acceleration trim within %f % of factory value\n\r", SelfTest[0]); 00171 LOG("y-axis self test: acceleration trim within %f % of factory value\n\r", SelfTest[1]); 00172 LOG("z-axis self test: acceleration trim within %f % of factory value\n\r", SelfTest[2]); 00173 LOG("x-axis self test: gyration trim within %f % of factory value\n\r", SelfTest[3]); 00174 LOG("y-axis self test: gyration trim within %f % of factory value\n\r", SelfTest[4]); 00175 LOG("z-axis self test: gyration trim within %f % of factory value\n\r", SelfTest[5]); 00176 wait(1); 00177 MPU9150.resetMPU9150(); // Reset registers to default in preparation for device calibration 00178 MPU9150.calibrateMPU9150(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers 00179 LOG("x gyro bias = %f\n\r", gyroBias[0]); 00180 LOG("y gyro bias = %f\n\r", gyroBias[1]); 00181 LOG("z gyro bias = %f\n\r", gyroBias[2]); 00182 LOG("x accel bias = %f\n\r", accelBias[0]); 00183 LOG("y accel bias = %f\n\r", accelBias[1]); 00184 LOG("z accel bias = %f\n\r", accelBias[2]); 00185 wait(1); 00186 MPU9150.initMPU9150(); 00187 LOG("MPU9150 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature 00188 MPU9150.initAK8975A(magCalibration); 00189 oled.writeString(2,0,"Mag Cal, wave 8"); 00190 MPU9150.magcalMPU9150(magBias); 00191 oled.writeString(2,0,"Mag Cal done "); 00192 wait(1); 00193 LOG("AK8975 initialized for active data mode....\n\r"); // Initialize device for active mode read of magnetometer 00194 } else { 00195 LOG("Could not connect to MPU9150: \n\r"); 00196 LOG("%#x \n", whoami); 00197 00198 //lcd.clear(); 00199 //lcd.printString("MPU9150", 0, 0); 00200 //lcd.printString("no connection", 0, 1); 00201 sprintf(buffer, "WHO_AM_I 0x%x", whoami); 00202 //lcd.printString(buffer, 0, 2); 00203 00204 while(1) ; // Loop forever if communication doesn't happen 00205 } 00206 00207 uint8_t MagRate = 10; // set magnetometer read rate in Hz; 10 to 100 (max) Hz are reasonable values 00208 MPU9150.getAres(); // Get accelerometer sensitivity 00209 MPU9150.getGres(); // Get gyro sensitivity 00210 mRes = 10.*1229./4096.; // Conversion from 1229 microTesla full scale (4096) to 12.29 Gauss full scale 00211 // So far, magnetometer bias is calculated and subtracted here manually, should construct an algorithm to do it automatically 00212 // like the gyro and accelerometer biases 00213 00214 //Wait for GPS to acquire lock 00215 oled.writeString(2,0,"GPS Waiting..."); 00216 while(!myGPS.fix) { 00217 c = myGPS.read(); //queries the GPS 00218 if (c) { 00219 LOG("%c", c); //this line will echo the GPS data if not paused 00220 } 00221 00222 //check if we recieved a new message from GPS, if so, attempt to parse it, 00223 if ( myGPS.newNMEAreceived() ) { 00224 if ( !myGPS.parse(myGPS.lastNMEA()) ) { 00225 continue; 00226 } 00227 } 00228 /* 00229 Now = t.read_us(); 00230 deltat = (float)((Now - lastUpdate)/1000000.0f); 00231 00232 bool up = false; 00233 if(deltat > 0.5f) 00234 { 00235 bmp.update(); 00236 float temp = bmp.get_temperature(); 00237 float pres = bmp.get_pressure(); 00238 float baroAlt = (float)44330 * (1 - pow((float)(pres/SEA_PRES), 0.190295f)); 00239 00240 sprintf(buffer,"ALT:%5.2f",baroAlt); 00241 oled.writeString(4,0,buffer); 00242 sprintf(buffer,"TMP:%5.2f",temp); 00243 oled.writeString(5,0,buffer); 00244 sprintf(buffer,"PRS:%5.2f",pres); 00245 oled.writeString(6,0,buffer); 00246 00247 serial_spi_nikon.printf("$GPRMC,000002.000,A,3456.9076,S,13831.2800,E,0.00,65.44,240215,,,D*49\r\n"); 00248 serial_spi_nikon.printf("$PTNTHPR,105.0,N,-21.4,N,0.9,N,A*79\r\n"); 00249 wait(0.1); 00250 //serial_spi_nikon.printf("$GPVTG,65.44,T,,M,0.00,N,0.00,K,D*0B"); 00251 sprintf(buffer+1,"GPGGA,000002.000,3456.9076,S,13831.2800,E,2,07,0.94,%5.2f,M,-0.5,M,,",baroAlt); 00252 int checkS = checkSum(buffer+1,strlen(buffer+1)); 00253 buffer[0] = '$'; 00254 serial_spi_nikon.printf(buffer); 00255 serial_spi_nikon.printf("*%02X\r\n",checkS); 00256 wait(0.1); 00257 serial_spi_nikon.printf("$GPGSA,A,3,13,15,24,06,12,02,28,,,,,,1.32,0.94,0.92*09\r\n"); 00258 serial_spi_nikon.printf("$GPGLL,3456.9076,S,13831.2800,E,000002.000,A,D*4D\r\n"); 00259 serial_spi_nikon.printf("$NKGCS,WGS 84*11\r\n"); 00260 00261 if(up) 00262 { 00263 serial_spi_nikon.ioSetState(0x0); 00264 up = false; 00265 } 00266 else 00267 { 00268 serial_spi_nikon.ioSetState(0x3); 00269 up = true; 00270 } 00271 lastUpdate = Now; 00272 } 00273 */ 00274 } 00275 00276 mkdir("/sd/logdir", 0777); 00277 sprintf(buffer,"/sd/logdir/%d%d20%d_%d%d%d.txt",myGPS.day, myGPS.month, myGPS.year, 00278 myGPS.hour, myGPS.minute, myGPS.seconds); 00279 FILE *fp = fopen(buffer, "w"); 00280 if(fp == NULL) { 00281 LOG("Could not open file for write\n"); 00282 oled.writeString(7,0,"SD Fail"); 00283 } else { 00284 oled.writeString(7,0,"SD OKAY"); 00285 } 00286 00287 while(1) { 00288 c = myGPS.read(); //queries the GPS 00289 if (c) { 00290 LOG("%c", c); //this line will echo the GPS data if not paused 00291 //serial_spi_nikon.putc(c); 00292 //serial_spi_nikon.printf("$GPGGA,154850.00,3452.12190,S,13836.65170,E,1,04,1.64,123.5,M,0.0,M,,*7F\r\n"); 00293 //$GPGGA,160202.00,3452.14414,S,13836.63059,E,1,04,2.60,45.4,M,-3.4,M,,*6B 00294 //serial_spi_nikon.printf("$GPRMC,154850.00,A,3452.12190,S,13836.65170,E,0.510,,110215,,,A*63\r\n"); 00295 //$GPRMC,160203.00,A,3452.14414,S,13836.63079,E,0.332,,110215,,,A*6F 00296 } 00297 00298 // If intPin goes high, all data registers have new data 00299 if(MPU9150.readByte(MPU9150_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt 00300 00301 MPU9150.readAccelData(accelCount); // Read the x/y/z adc values 00302 // Now we'll calculate the accleration value into actual g's 00303 ax = (float)accelCount[0]*aRes; // - accelBias[0]; // get actual g value, this depends on scale being set 00304 ay = (float)accelCount[1]*aRes; // - accelBias[1]; 00305 az = (float)accelCount[2]*aRes; // - accelBias[2]; 00306 00307 MPU9150.readGyroData(gyroCount); // Read the x/y/z adc values 00308 // Calculate the gyro value into actual degrees per second 00309 gx = (float)gyroCount[0]*gRes; // - gyroBias[0]; // get actual gyro value, this depends on scale being set 00310 gy = (float)gyroCount[1]*gRes; // - gyroBias[1]; 00311 gz = (float)gyroCount[2]*gRes; // - gyroBias[2]; 00312 00313 mcount++; 00314 if (mcount > 200/MagRate) { // this is a poor man's way of setting the magnetometer read rate (see below) 00315 MPU9150.readMagData(magCount); // Read the x/y/z adc values 00316 // Calculate the magnetometer values in milliGauss 00317 // Include factory calibration per data sheet and user environmental corrections 00318 mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0]; // get actual magnetometer value, this depends on scale being set 00319 my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1]; 00320 mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2]; 00321 mcount = 0; 00322 } 00323 } 00324 00325 //Handle GPS data 00326 { 00327 c = myGPS.read(); //queries the GPS 00328 if (c) { 00329 LOG("%c", c); //this line will echo the GPS data if not paused 00330 //serial_spi_nikon.putc(c); 00331 } 00332 00333 //check if we recieved a new message from GPS, if so, attempt to parse it, 00334 if ( myGPS.newNMEAreceived() ) { 00335 if ( !myGPS.parse(myGPS.lastNMEA()) ) { 00336 continue; 00337 } 00338 00339 else 00340 { 00341 serial_spi_nikon.printf(myGPS.lastNMEA()); 00342 serial_spi_nikon.printf("\n\r"); 00343 00344 serial_spi_ble.printf(myGPS.lastNMEA()); 00345 serial_spi_ble.printf("\n\r"); 00346 00347 if(myGPS.fix && fp!=NULL) { 00348 fprintf(fp,myGPS.lastNMEA()); 00349 fprintf(fp,"\r\n"); 00350 } 00351 } 00352 00353 } 00354 } 00355 00356 Now = t.read_us(); 00357 deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update 00358 lastUpdate = Now; 00359 00360 sum += deltat; 00361 sumCount++; 00362 00363 // if(lastUpdate - firstUpdate > 10000000.0f) { 00364 // beta = 0.04; // decrease filter gain after stabilized 00365 // zeta = 0.015; // increasey bias drift gain after stabilized 00366 // } 00367 00368 // Pass gyro rate as rad/s 00369 MPU9150.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); 00370 // MPU9150.MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); 00371 00372 // Serial print and/or display at 0.5 s rate independent of data rates 00373 delt_t = t.read_ms() - count; 00374 if (delt_t > 500) { // update LCD once per half-second independent of read rate 00375 00376 LOG("ax = %f", 1000*ax); 00377 LOG(" ay = %f", 1000*ay); 00378 LOG(" az = %f mg\n\r", 1000*az); 00379 00380 LOG("gx = %f", gx); 00381 LOG(" gy = %f", gy); 00382 LOG(" gz = %f deg/s\n\r", gz); 00383 00384 LOG("gx = %f", mx); 00385 LOG(" gy = %f", my); 00386 LOG(" gz = %f mG\n\r", mz); 00387 00388 tempCount = MPU9150.readTempData(); // Read the adc values 00389 temperature = ((float) tempCount) / 340.0f + 36.53f; // Temperature in degrees Centigrade 00390 LOG(" temperature = %f C\n\r", temperature); 00391 00392 LOG("q0 = %f\n\r", q[0]); 00393 LOG("q1 = %f\n\r", q[1]); 00394 LOG("q2 = %f\n\r", q[2]); 00395 LOG("q3 = %f\n\r", q[3]); 00396 00397 // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. 00398 // In this coordinate system, the positive z-axis is down toward Earth. 00399 // 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. 00400 // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. 00401 // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. 00402 // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. 00403 // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be 00404 // applied in the correct order which for this configuration is yaw, pitch, and then roll. 00405 // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. 00406 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]); 00407 pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); 00408 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]); 00409 pitch *= 180.0f / PI; 00410 yaw *= 180.0f / PI; 00411 yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 00412 roll *= 180.0f / PI; 00413 00414 00415 LOG("Yaw, Pitch, Roll: %f %f %f\r\n", yaw, pitch, roll); 00416 LOG("average rate = %f\r\n", (float) sumCount/sum); 00417 00418 sprintf(buffer, "YPR:%3.0f %3.0f %3.0f", yaw, pitch, roll); 00419 oled.writeString(1,0,buffer); 00420 sprintf(buffer+1,"PTNTHPR,%3.1f,N,%3.1f,N,%3.1f,N,A",yaw,pitch,roll); 00421 int checkS = checkSum(buffer+1,strlen(buffer+1)); 00422 buffer[0] = '$'; 00423 serial_spi_nikon.printf(buffer); 00424 serial_spi_nikon.printf("*%02X\r\n",checkS); 00425 00426 serial_spi_ble.printf(buffer); 00427 serial_spi_ble.printf("*%02X\r\n",checkS); 00428 00429 if(fp != NULL) { 00430 fprintf(fp,"%s%02X\r\n",buffer,checkS); 00431 if(fflush(fp)==EOF) { 00432 //SD card removed close file pointer 00433 oled.writeString(7,0,"SD Fail"); 00434 fp=NULL; 00435 } 00436 } 00437 00438 LOG("Time: %d:%d:%d.%u\n", myGPS.hour, myGPS.minute, myGPS.seconds, myGPS.milliseconds); 00439 LOG("Date: %d/%d/20%d\n", myGPS.day, myGPS.month, myGPS.year); 00440 LOG("Fix: %d\n", (int) myGPS.fix); 00441 LOG("Quality: %d\n", (int) myGPS.fixquality); 00442 if (myGPS.fix) { 00443 LOG("Location: %5.2f%c, %5.2f%c\n", myGPS.latitude, myGPS.lat, myGPS.longitude, myGPS.lon); 00444 LOG("Speed: %5.2f knots\n", myGPS.speed); 00445 LOG("Angle: %5.2f\n", myGPS.angle); 00446 LOG("Altitude: %5.2f\n", myGPS.altitude); 00447 LOG("Satellites: %d\n", myGPS.satellites); 00448 } 00449 00450 if (myGPS.fix) { 00451 sprintf(buffer,"LAT:%5.5f%c",myGPS.latitude,myGPS.lat); 00452 oled.writeString(2,0,buffer); 00453 sprintf(buffer,"LON:%5.5f%c",myGPS.longitude,myGPS.lon); 00454 oled.writeString(3,0,buffer); 00455 sprintf(buffer,"ALT:%5.2f",myGPS.altitude); 00456 oled.writeString(4,0,buffer); 00457 } else { 00458 oled.writeString(2,0," "); 00459 oled.writeString(2,0,"GPS Lost "); 00460 oled.writeString(3,0," "); 00461 oled.writeString(4,0," "); 00462 } 00463 sprintf(buffer,"Time: %d:%d:%d.%u\n", myGPS.hour, myGPS.minute, myGPS.seconds, myGPS.milliseconds); 00464 oled.writeString(5,0,buffer); 00465 sprintf(buffer,"Date: %d/%d/20%d\n", myGPS.day, myGPS.month, myGPS.year); 00466 oled.writeString(6,0,buffer); 00467 00468 if(fp != NULL) { 00469 if(fflush(fp)==EOF) { 00470 //SD card removed close file pointer 00471 oled.writeString(7,0,"SD Fail"); 00472 fp=NULL; 00473 } 00474 } 00475 00476 //if FP is null at the end of the loop attempt to open new log with fix 00477 if(fp==NULL && myGPS.fix) { 00478 mkdir("/sd/logdir", 0777); 00479 sprintf(buffer,"/sd/logdir/%d%d20%d_%d%d%d.txt",myGPS.day, myGPS.month, myGPS.year, 00480 myGPS.hour, myGPS.minute, myGPS.seconds); 00481 FILE *fp = fopen(buffer, "w"); 00482 if(fp == NULL) { 00483 LOG("Could not open file for write\n"); 00484 oled.writeString(7,0,"SD Fail"); 00485 } else { 00486 oled.writeString(7,0,"SD OKAY"); 00487 } 00488 } 00489 00490 myled= !myled; 00491 count = t.read_ms(); 00492 00493 if(count > 1<<21) { 00494 t.start(); // start the timer over again if ~30 minutes has passed 00495 count = 0; 00496 deltat= 0; 00497 lastUpdate = t.read_us(); 00498 } 00499 sum = 0; 00500 sumCount = 0; 00501 00502 } 00503 } 00504 } 00505
Generated on Mon Jul 18 2022 08:59:16 by 1.7.2