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:
Tue Dec 01 04:49:10 2015 +0000
Revision:
10:46b5acee9472
Parent:
9:b7062c55d36c
Minor text changes

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