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 Nov 18 14:21:32 2014 +0000
Revision:
1:9de6ac4b381d
Parent:
0:39935bb3c1a1
Child:
2:f1912528eeaf
Added SD file system and GPS

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"
onehorse 0:39935bb3c1a1 36
whatnick 1:9de6ac4b381d 37 //Use Xadow OLED for display
whatnick 1:9de6ac4b381d 38 SSD1308 oled = SSD1308(i2c, SSD1308_SA0);
whatnick 1:9de6ac4b381d 39
whatnick 1:9de6ac4b381d 40 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 41
onehorse 0:39935bb3c1a1 42 float sum = 0;
onehorse 0:39935bb3c1a1 43 uint32_t sumCount = 0, mcount = 0;
whatnick 1:9de6ac4b381d 44 char buffer[32];
whatnick 1:9de6ac4b381d 45
whatnick 1:9de6ac4b381d 46 MPU9150 MPU9150;
onehorse 0:39935bb3c1a1 47
whatnick 1:9de6ac4b381d 48 Timer t;
whatnick 1:9de6ac4b381d 49
whatnick 1:9de6ac4b381d 50 Serial gps(P0_19,P0_18);
whatnick 1:9de6ac4b381d 51 char msg[256];
onehorse 0:39935bb3c1a1 52
whatnick 1:9de6ac4b381d 53 #define DEBUG
onehorse 0:39935bb3c1a1 54
whatnick 1:9de6ac4b381d 55 #ifdef DEBUG
whatnick 1:9de6ac4b381d 56 #include "USBSerial.h" // To use USB virtual serial, a driver is needed, check http://mbed.org/handbook/USBSerial
whatnick 1:9de6ac4b381d 57 #define LOG(args...) pc.printf(args)
whatnick 1:9de6ac4b381d 58 USBSerial pc;
whatnick 1:9de6ac4b381d 59 #else
whatnick 1:9de6ac4b381d 60 #define LOG(args...)
whatnick 1:9de6ac4b381d 61 #endif
onehorse 0:39935bb3c1a1 62
onehorse 0:39935bb3c1a1 63 int main()
onehorse 0:39935bb3c1a1 64 {
whatnick 1:9de6ac4b381d 65
whatnick 1:9de6ac4b381d 66 //Set up I2C
whatnick 1:9de6ac4b381d 67 i2c.frequency(400000); // use fast (400 kHz) I2C
whatnick 1:9de6ac4b381d 68
whatnick 1:9de6ac4b381d 69
whatnick 1:9de6ac4b381d 70 pc.printf("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock);
onehorse 0:39935bb3c1a1 71
whatnick 1:9de6ac4b381d 72 t.start();
whatnick 1:9de6ac4b381d 73
whatnick 1:9de6ac4b381d 74 oled.writeString(0, 0, "##AeroAHRS##");
whatnick 1:9de6ac4b381d 75
whatnick 1:9de6ac4b381d 76 oled.fillDisplay(0xAA);
whatnick 1:9de6ac4b381d 77 oled.setDisplayOff();
onehorse 0:39935bb3c1a1 78 wait(1);
whatnick 1:9de6ac4b381d 79 oled.setDisplayOn();
whatnick 1:9de6ac4b381d 80
whatnick 1:9de6ac4b381d 81 oled.clearDisplay();
whatnick 1:9de6ac4b381d 82 oled.setDisplayInverse();
whatnick 1:9de6ac4b381d 83 wait(0.5);
whatnick 1:9de6ac4b381d 84 oled.setDisplayNormal();
whatnick 1:9de6ac4b381d 85
whatnick 1:9de6ac4b381d 86 oled.writeBitmap((uint8_t*) mbed_logo);
whatnick 1:9de6ac4b381d 87
whatnick 1:9de6ac4b381d 88 pc.printf("OLED test done\r\n");
whatnick 1:9de6ac4b381d 89 wait(10);
whatnick 1:9de6ac4b381d 90 oled.clearDisplay();
whatnick 1:9de6ac4b381d 91
whatnick 1:9de6ac4b381d 92
whatnick 1:9de6ac4b381d 93 // Read the WHO_AM_I register, this is a good test of communication
whatnick 1:9de6ac4b381d 94 uint8_t whoami = MPU9150.readByte(MPU9150_ADDRESS, WHO_AM_I_MPU9150); // Read WHO_AM_I register for MPU-9250
whatnick 1:9de6ac4b381d 95 pc.printf("I AM 0x%x\n\r", whoami);
whatnick 1:9de6ac4b381d 96 pc.printf("I SHOULD BE 0x68\n\r");
whatnick 1:9de6ac4b381d 97
whatnick 1:9de6ac4b381d 98 if (whoami == 0x68) { // WHO_AM_I should be 0x68
whatnick 1:9de6ac4b381d 99 pc.printf("MPU9150 WHO_AM_I is 0x%x\n\r", whoami);
whatnick 1:9de6ac4b381d 100 pc.printf("MPU9150 is online...\n\r");
whatnick 1:9de6ac4b381d 101 //lcd.clear();
whatnick 1:9de6ac4b381d 102 //lcd.printString("MPU9150 is", 0, 0);
whatnick 1:9de6ac4b381d 103 //sprintf(buffer, "0x%x", whoami);
whatnick 1:9de6ac4b381d 104 //lcd.printString(buffer, 0, 1);
whatnick 1:9de6ac4b381d 105 //lcd.printString("shoud be 0x68", 0, 2);
whatnick 1:9de6ac4b381d 106 wait(1);
whatnick 1:9de6ac4b381d 107
whatnick 1:9de6ac4b381d 108 MPU9150.MPU9150SelfTest(SelfTest);
whatnick 1:9de6ac4b381d 109 pc.printf("x-axis self test: acceleration trim within %f % of factory value\n\r", SelfTest[0]);
whatnick 1:9de6ac4b381d 110 pc.printf("y-axis self test: acceleration trim within %f % of factory value\n\r", SelfTest[1]);
whatnick 1:9de6ac4b381d 111 pc.printf("z-axis self test: acceleration trim within %f % of factory value\n\r", SelfTest[2]);
whatnick 1:9de6ac4b381d 112 pc.printf("x-axis self test: gyration trim within %f % of factory value\n\r", SelfTest[3]);
whatnick 1:9de6ac4b381d 113 pc.printf("y-axis self test: gyration trim within %f % of factory value\n\r", SelfTest[4]);
whatnick 1:9de6ac4b381d 114 pc.printf("z-axis self test: gyration trim within %f % of factory value\n\r", SelfTest[5]);
whatnick 1:9de6ac4b381d 115 wait(1);
whatnick 1:9de6ac4b381d 116 MPU9150.resetMPU9150(); // Reset registers to default in preparation for device calibration
whatnick 1:9de6ac4b381d 117 MPU9150.calibrateMPU9150(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers
whatnick 1:9de6ac4b381d 118 pc.printf("x gyro bias = %f\n\r", gyroBias[0]);
whatnick 1:9de6ac4b381d 119 pc.printf("y gyro bias = %f\n\r", gyroBias[1]);
whatnick 1:9de6ac4b381d 120 pc.printf("z gyro bias = %f\n\r", gyroBias[2]);
whatnick 1:9de6ac4b381d 121 pc.printf("x accel bias = %f\n\r", accelBias[0]);
whatnick 1:9de6ac4b381d 122 pc.printf("y accel bias = %f\n\r", accelBias[1]);
whatnick 1:9de6ac4b381d 123 pc.printf("z accel bias = %f\n\r", accelBias[2]);
whatnick 1:9de6ac4b381d 124 wait(1);
whatnick 1:9de6ac4b381d 125 MPU9150.initMPU9150();
whatnick 1:9de6ac4b381d 126 pc.printf("MPU9150 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature
whatnick 1:9de6ac4b381d 127 MPU9150.initAK8975A(magCalibration);
whatnick 1:9de6ac4b381d 128 pc.printf("AK8975 initialized for active data mode....\n\r"); // Initialize device for active mode read of magnetometer
whatnick 1:9de6ac4b381d 129 } else {
whatnick 1:9de6ac4b381d 130 pc.printf("Could not connect to MPU9150: \n\r");
whatnick 1:9de6ac4b381d 131 pc.printf("%#x \n", whoami);
whatnick 1:9de6ac4b381d 132
whatnick 1:9de6ac4b381d 133 //lcd.clear();
whatnick 1:9de6ac4b381d 134 //lcd.printString("MPU9150", 0, 0);
whatnick 1:9de6ac4b381d 135 //lcd.printString("no connection", 0, 1);
whatnick 1:9de6ac4b381d 136 sprintf(buffer, "WHO_AM_I 0x%x", whoami);
whatnick 1:9de6ac4b381d 137 //lcd.printString(buffer, 0, 2);
whatnick 1:9de6ac4b381d 138
whatnick 1:9de6ac4b381d 139 while(1) ; // Loop forever if communication doesn't happen
onehorse 0:39935bb3c1a1 140 }
onehorse 0:39935bb3c1a1 141
onehorse 0:39935bb3c1a1 142 uint8_t MagRate = 10; // set magnetometer read rate in Hz; 10 to 100 (max) Hz are reasonable values
onehorse 0:39935bb3c1a1 143 MPU9150.getAres(); // Get accelerometer sensitivity
onehorse 0:39935bb3c1a1 144 MPU9150.getGres(); // Get gyro sensitivity
onehorse 0:39935bb3c1a1 145 mRes = 10.*1229./4096.; // Conversion from 1229 microTesla full scale (4096) to 12.29 Gauss full scale
onehorse 0:39935bb3c1a1 146 // So far, magnetometer bias is calculated and subtracted here manually, should construct an algorithm to do it automatically
onehorse 0:39935bb3c1a1 147 // like the gyro and accelerometer biases
onehorse 0:39935bb3c1a1 148 magbias[0] = -5.; // User environmental x-axis correction in milliGauss
onehorse 0:39935bb3c1a1 149 magbias[1] = -95.; // User environmental y-axis correction in milliGauss
onehorse 0:39935bb3c1a1 150 magbias[2] = -260.; // User environmental z-axis correction in milliGauss
whatnick 1:9de6ac4b381d 151
whatnick 1:9de6ac4b381d 152 mkdir("/sd/logdir", 0777);
whatnick 1:9de6ac4b381d 153 FILE *fp = fopen("/sd/logdir/IMULog.txt", "w");
whatnick 1:9de6ac4b381d 154 if(fp == NULL) {
whatnick 1:9de6ac4b381d 155 LOG("Could not open file for write\n");
whatnick 1:9de6ac4b381d 156 oled.writeString(7,0,"SD Fail");
whatnick 1:9de6ac4b381d 157 }
onehorse 0:39935bb3c1a1 158
whatnick 1:9de6ac4b381d 159 while(1) {
whatnick 1:9de6ac4b381d 160
whatnick 1:9de6ac4b381d 161 // If intPin goes high, all data registers have new data
whatnick 1:9de6ac4b381d 162 if(MPU9150.readByte(MPU9150_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt
whatnick 1:9de6ac4b381d 163
whatnick 1:9de6ac4b381d 164 MPU9150.readAccelData(accelCount); // Read the x/y/z adc values
whatnick 1:9de6ac4b381d 165 // Now we'll calculate the accleration value into actual g's
whatnick 1:9de6ac4b381d 166 ax = (float)accelCount[0]*aRes; // - accelBias[0]; // get actual g value, this depends on scale being set
whatnick 1:9de6ac4b381d 167 ay = (float)accelCount[1]*aRes; // - accelBias[1];
whatnick 1:9de6ac4b381d 168 az = (float)accelCount[2]*aRes; // - accelBias[2];
onehorse 0:39935bb3c1a1 169
whatnick 1:9de6ac4b381d 170 MPU9150.readGyroData(gyroCount); // Read the x/y/z adc values
whatnick 1:9de6ac4b381d 171 // Calculate the gyro value into actual degrees per second
whatnick 1:9de6ac4b381d 172 gx = (float)gyroCount[0]*gRes; // - gyroBias[0]; // get actual gyro value, this depends on scale being set
whatnick 1:9de6ac4b381d 173 gy = (float)gyroCount[1]*gRes; // - gyroBias[1];
whatnick 1:9de6ac4b381d 174 gz = (float)gyroCount[2]*gRes; // - gyroBias[2];
whatnick 1:9de6ac4b381d 175
whatnick 1:9de6ac4b381d 176 mcount++;
whatnick 1:9de6ac4b381d 177 if (mcount > 200/MagRate) { // this is a poor man's way of setting the magnetometer read rate (see below)
whatnick 1:9de6ac4b381d 178 MPU9150.readMagData(magCount); // Read the x/y/z adc values
whatnick 1:9de6ac4b381d 179 // Calculate the magnetometer values in milliGauss
whatnick 1:9de6ac4b381d 180 // Include factory calibration per data sheet and user environmental corrections
whatnick 1:9de6ac4b381d 181 mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0]; // get actual magnetometer value, this depends on scale being set
whatnick 1:9de6ac4b381d 182 my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1];
whatnick 1:9de6ac4b381d 183 mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2];
whatnick 1:9de6ac4b381d 184 mcount = 0;
whatnick 1:9de6ac4b381d 185 }
whatnick 1:9de6ac4b381d 186 }
whatnick 1:9de6ac4b381d 187
whatnick 1:9de6ac4b381d 188 Now = t.read_us();
whatnick 1:9de6ac4b381d 189 deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update
whatnick 1:9de6ac4b381d 190 lastUpdate = Now;
whatnick 1:9de6ac4b381d 191
whatnick 1:9de6ac4b381d 192 sum += deltat;
whatnick 1:9de6ac4b381d 193 sumCount++;
whatnick 1:9de6ac4b381d 194
onehorse 0:39935bb3c1a1 195 // if(lastUpdate - firstUpdate > 10000000.0f) {
onehorse 0:39935bb3c1a1 196 // beta = 0.04; // decrease filter gain after stabilized
onehorse 0:39935bb3c1a1 197 // zeta = 0.015; // increasey bias drift gain after stabilized
whatnick 1:9de6ac4b381d 198 // }
whatnick 1:9de6ac4b381d 199
whatnick 1:9de6ac4b381d 200 // Pass gyro rate as rad/s
whatnick 1:9de6ac4b381d 201 MPU9150.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
whatnick 1:9de6ac4b381d 202 // MPU9150.MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
whatnick 1:9de6ac4b381d 203
whatnick 1:9de6ac4b381d 204 // Serial print and/or display at 0.5 s rate independent of data rates
whatnick 1:9de6ac4b381d 205 delt_t = t.read_ms() - count;
whatnick 1:9de6ac4b381d 206 if (delt_t > 500) { // update LCD once per half-second independent of read rate
whatnick 1:9de6ac4b381d 207
whatnick 1:9de6ac4b381d 208 pc.printf("ax = %f", 1000*ax);
whatnick 1:9de6ac4b381d 209 pc.printf(" ay = %f", 1000*ay);
whatnick 1:9de6ac4b381d 210 pc.printf(" az = %f mg\n\r", 1000*az);
onehorse 0:39935bb3c1a1 211
whatnick 1:9de6ac4b381d 212 pc.printf("gx = %f", gx);
whatnick 1:9de6ac4b381d 213 pc.printf(" gy = %f", gy);
whatnick 1:9de6ac4b381d 214 pc.printf(" gz = %f deg/s\n\r", gz);
whatnick 1:9de6ac4b381d 215
whatnick 1:9de6ac4b381d 216 pc.printf("gx = %f", mx);
whatnick 1:9de6ac4b381d 217 pc.printf(" gy = %f", my);
whatnick 1:9de6ac4b381d 218 pc.printf(" gz = %f mG\n\r", mz);
onehorse 0:39935bb3c1a1 219
whatnick 1:9de6ac4b381d 220 tempCount = MPU9150.readTempData(); // Read the adc values
whatnick 1:9de6ac4b381d 221 temperature = ((float) tempCount) / 340.0f + 36.53f; // Temperature in degrees Centigrade
whatnick 1:9de6ac4b381d 222 pc.printf(" temperature = %f C\n\r", temperature);
whatnick 1:9de6ac4b381d 223
whatnick 1:9de6ac4b381d 224 pc.printf("q0 = %f\n\r", q[0]);
whatnick 1:9de6ac4b381d 225 pc.printf("q1 = %f\n\r", q[1]);
whatnick 1:9de6ac4b381d 226 pc.printf("q2 = %f\n\r", q[2]);
whatnick 1:9de6ac4b381d 227 pc.printf("q3 = %f\n\r", q[3]);
onehorse 0:39935bb3c1a1 228
whatnick 1:9de6ac4b381d 229 /* lcd.clear();
whatnick 1:9de6ac4b381d 230 lcd.printString("MPU9150", 0, 0);
whatnick 1:9de6ac4b381d 231 lcd.printString("x y z", 0, 1);
whatnick 1:9de6ac4b381d 232 sprintf(buffer, "%d %d %d mg", (int)(1000.0f*ax), (int)(1000.0f*ay), (int)(1000.0f*az));
whatnick 1:9de6ac4b381d 233 lcd.printString(buffer, 0, 2);
whatnick 1:9de6ac4b381d 234 sprintf(buffer, "%d %d %d deg/s", (int)gx, (int)gy, (int)gz);
whatnick 1:9de6ac4b381d 235 lcd.printString(buffer, 0, 3);
whatnick 1:9de6ac4b381d 236 sprintf(buffer, "%d %d %d mG", (int)mx, (int)my, (int)mz);
whatnick 1:9de6ac4b381d 237 lcd.printString(buffer, 0, 4);
whatnick 1:9de6ac4b381d 238 */
whatnick 1:9de6ac4b381d 239 // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation.
whatnick 1:9de6ac4b381d 240 // In this coordinate system, the positive z-axis is down toward Earth.
whatnick 1:9de6ac4b381d 241 // 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 242 // 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 243 // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll.
whatnick 1:9de6ac4b381d 244 // These arise from the definition of the homogeneous rotation matrix constructed from quaternions.
whatnick 1:9de6ac4b381d 245 // 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 246 // applied in the correct order which for this configuration is yaw, pitch, and then roll.
whatnick 1:9de6ac4b381d 247 // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links.
whatnick 1:9de6ac4b381d 248 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 249 pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
whatnick 1:9de6ac4b381d 250 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 251 pitch *= 180.0f / PI;
whatnick 1:9de6ac4b381d 252 yaw *= 180.0f / PI;
whatnick 1:9de6ac4b381d 253 yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04
whatnick 1:9de6ac4b381d 254 roll *= 180.0f / PI;
onehorse 0:39935bb3c1a1 255
whatnick 1:9de6ac4b381d 256
whatnick 1:9de6ac4b381d 257 pc.printf("Yaw, Pitch, Roll: %f %f %f\n\r", yaw, pitch, roll);
whatnick 1:9de6ac4b381d 258 pc.printf("average rate = %f\n\r", (float) sumCount/sum);
whatnick 1:9de6ac4b381d 259
whatnick 1:9de6ac4b381d 260 sprintf(buffer, "YPR: %.2f %.2f %.2f", yaw, pitch, roll);
whatnick 1:9de6ac4b381d 261 oled.writeString(0, 0, "##AeroAHRS##");
whatnick 1:9de6ac4b381d 262 oled.writeString(1,0,buffer);
onehorse 0:39935bb3c1a1 263 // lcd.printString(buffer, 0, 4);
onehorse 0:39935bb3c1a1 264 // sprintf(buffer, "rate = %f", (float) sumCount/sum);
onehorse 0:39935bb3c1a1 265 // lcd.printString(buffer, 0, 5);
whatnick 1:9de6ac4b381d 266
whatnick 1:9de6ac4b381d 267 myled= !myled;
whatnick 1:9de6ac4b381d 268 count = t.read_ms();
onehorse 0:39935bb3c1a1 269
whatnick 1:9de6ac4b381d 270 if(count > 1<<21) {
whatnick 1:9de6ac4b381d 271 t.start(); // start the timer over again if ~30 minutes has passed
whatnick 1:9de6ac4b381d 272 count = 0;
whatnick 1:9de6ac4b381d 273 deltat= 0;
whatnick 1:9de6ac4b381d 274 lastUpdate = t.read_us();
whatnick 1:9de6ac4b381d 275 }
whatnick 1:9de6ac4b381d 276 sum = 0;
whatnick 1:9de6ac4b381d 277 sumCount = 0;
whatnick 1:9de6ac4b381d 278 }
onehorse 0:39935bb3c1a1 279 }
whatnick 1:9de6ac4b381d 280
whatnick 1:9de6ac4b381d 281 }