Basic program to obtain properly-scaled gyro, accelerometer, and magnetometer data from the MPU-9250 9-axis motion sensor and do 9 DoF sensor fusion using the open-source Madgwick and Mahony sensor fusion filters. Running on STM32F401RE Nucleo board at 84 MHz achieves sensor fusion filter update rates of ~5000 Hz.

Dependencies:   ST_401_84MHZ mbed

Committer:
onehorse
Date:
Tue Aug 05 01:37:23 2014 +0000
Revision:
2:4e59a37182df
Parent:
1:71c319f03fda
Corrected self test

Who changed what in which revision?

UserRevisionLine numberNew contents of line
onehorse 0:2e5e65a6fb30 1 /* MPU9250 Basic Example Code
onehorse 0:2e5e65a6fb30 2 by: Kris Winer
onehorse 0:2e5e65a6fb30 3 date: April 1, 2014
onehorse 0:2e5e65a6fb30 4 license: Beerware - Use this code however you'd like. If you
onehorse 0:2e5e65a6fb30 5 find it useful you can buy me a beer some time.
onehorse 0:2e5e65a6fb30 6
onehorse 0:2e5e65a6fb30 7 Demonstrate basic MPU-9250 functionality including parameterizing the register addresses, initializing the sensor,
onehorse 0:2e5e65a6fb30 8 getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to
onehorse 0:2e5e65a6fb30 9 allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and
onehorse 0:2e5e65a6fb30 10 Mahony filter algorithms. Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1.
onehorse 0:2e5e65a6fb30 11
onehorse 0:2e5e65a6fb30 12 SDA and SCL should have external pull-up resistors (to 3.3V).
onehorse 0:2e5e65a6fb30 13 10k resistors are on the EMSENSR-9250 breakout board.
onehorse 0:2e5e65a6fb30 14
onehorse 0:2e5e65a6fb30 15 Hardware setup:
onehorse 0:2e5e65a6fb30 16 MPU9250 Breakout --------- Arduino
onehorse 0:2e5e65a6fb30 17 VDD ---------------------- 3.3V
onehorse 0:2e5e65a6fb30 18 VDDI --------------------- 3.3V
onehorse 0:2e5e65a6fb30 19 SDA ----------------------- A4
onehorse 0:2e5e65a6fb30 20 SCL ----------------------- A5
onehorse 0:2e5e65a6fb30 21 GND ---------------------- GND
onehorse 0:2e5e65a6fb30 22
onehorse 0:2e5e65a6fb30 23 Note: The MPU9250 is an I2C sensor and uses the Arduino Wire library.
onehorse 0:2e5e65a6fb30 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:2e5e65a6fb30 25 We have disabled the internal pull-ups used by the Wire library in the Wire.h/twi.c utility file.
onehorse 0:2e5e65a6fb30 26 We are also using the 400 kHz fast I2C mode by setting the TWI_FREQ to 400000L /twi.h utility file.
onehorse 0:2e5e65a6fb30 27 */
onehorse 0:2e5e65a6fb30 28
onehorse 0:2e5e65a6fb30 29 //#include "ST_F401_84MHZ.h"
onehorse 0:2e5e65a6fb30 30 //F401_init84 myinit(0);
onehorse 0:2e5e65a6fb30 31 #include "mbed.h"
onehorse 0:2e5e65a6fb30 32 #include "MPU9250.h"
onehorse 0:2e5e65a6fb30 33 #include "N5110.h"
onehorse 0:2e5e65a6fb30 34
onehorse 0:2e5e65a6fb30 35 // Using NOKIA 5110 monochrome 84 x 48 pixel display
onehorse 0:2e5e65a6fb30 36 // pin 9 - Serial clock out (SCLK)
onehorse 0:2e5e65a6fb30 37 // pin 8 - Serial data out (DIN)
onehorse 0:2e5e65a6fb30 38 // pin 7 - Data/Command select (D/C)
onehorse 0:2e5e65a6fb30 39 // pin 5 - LCD chip select (CS)
onehorse 0:2e5e65a6fb30 40 // pin 6 - LCD reset (RST)
onehorse 0:2e5e65a6fb30 41 //Adafruit_PCD8544 display = Adafruit_PCD8544(9, 8, 7, 5, 6);
onehorse 0:2e5e65a6fb30 42
onehorse 0:2e5e65a6fb30 43 float sum = 0;
onehorse 0:2e5e65a6fb30 44 uint32_t sumCount = 0;
onehorse 0:2e5e65a6fb30 45 char buffer[14];
onehorse 0:2e5e65a6fb30 46
onehorse 0:2e5e65a6fb30 47 MPU9250 mpu9250;
onehorse 0:2e5e65a6fb30 48
onehorse 0:2e5e65a6fb30 49 Timer t;
onehorse 0:2e5e65a6fb30 50
onehorse 0:2e5e65a6fb30 51 Serial pc(USBTX, USBRX); // tx, rx
onehorse 0:2e5e65a6fb30 52
onehorse 0:2e5e65a6fb30 53 // VCC, SCE, RST, D/C, MOSI,S CLK, LED
onehorse 0:2e5e65a6fb30 54 N5110 lcd(PA_8, PB_10, PA_9, PA_6, PA_7, PA_5, PC_7);
onehorse 0:2e5e65a6fb30 55
onehorse 0:2e5e65a6fb30 56
onehorse 0:2e5e65a6fb30 57
onehorse 0:2e5e65a6fb30 58 int main()
onehorse 0:2e5e65a6fb30 59 {
onehorse 0:2e5e65a6fb30 60 pc.baud(9600);
onehorse 0:2e5e65a6fb30 61
onehorse 0:2e5e65a6fb30 62 //Set up I2C
onehorse 0:2e5e65a6fb30 63 i2c.frequency(400000); // use fast (400 kHz) I2C
onehorse 0:2e5e65a6fb30 64
onehorse 0:2e5e65a6fb30 65 pc.printf("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock);
onehorse 0:2e5e65a6fb30 66
onehorse 0:2e5e65a6fb30 67 t.start();
onehorse 0:2e5e65a6fb30 68
onehorse 0:2e5e65a6fb30 69 lcd.init();
onehorse 0:2e5e65a6fb30 70 // lcd.setBrightness(0.05);
onehorse 0:2e5e65a6fb30 71
onehorse 0:2e5e65a6fb30 72
onehorse 0:2e5e65a6fb30 73 // Read the WHO_AM_I register, this is a good test of communication
onehorse 0:2e5e65a6fb30 74 uint8_t whoami = mpu9250.readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250); // Read WHO_AM_I register for MPU-9250
onehorse 0:2e5e65a6fb30 75 pc.printf("I AM 0x%x\n\r", whoami); pc.printf("I SHOULD BE 0x71\n\r");
onehorse 0:2e5e65a6fb30 76
onehorse 0:2e5e65a6fb30 77 if (whoami == 0x71) // WHO_AM_I should always be 0x68
onehorse 0:2e5e65a6fb30 78 {
onehorse 0:2e5e65a6fb30 79 pc.printf("MPU9250 WHO_AM_I is 0x%x\n\r", whoami);
onehorse 0:2e5e65a6fb30 80 pc.printf("MPU9250 is online...\n\r");
onehorse 0:2e5e65a6fb30 81 lcd.clear();
onehorse 0:2e5e65a6fb30 82 lcd.printString("MPU9250 is", 0, 0);
onehorse 0:2e5e65a6fb30 83 sprintf(buffer, "0x%x", whoami);
onehorse 0:2e5e65a6fb30 84 lcd.printString(buffer, 0, 1);
onehorse 0:2e5e65a6fb30 85 lcd.printString("shoud be 0x71", 0, 2);
onehorse 0:2e5e65a6fb30 86 wait(1);
onehorse 0:2e5e65a6fb30 87
onehorse 0:2e5e65a6fb30 88 mpu9250.resetMPU9250(); // Reset registers to default in preparation for device calibration
onehorse 1:71c319f03fda 89 mpu9250.MPU9250SelfTest(SelfTest); // Start by performing self test and reporting values
onehorse 1:71c319f03fda 90 pc.printf("x-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[0]);
onehorse 1:71c319f03fda 91 pc.printf("y-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[1]);
onehorse 1:71c319f03fda 92 pc.printf("z-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[2]);
onehorse 1:71c319f03fda 93 pc.printf("x-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[3]);
onehorse 1:71c319f03fda 94 pc.printf("y-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[4]);
onehorse 1:71c319f03fda 95 pc.printf("z-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[5]);
onehorse 0:2e5e65a6fb30 96 mpu9250.calibrateMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers
onehorse 0:2e5e65a6fb30 97 pc.printf("x gyro bias = %f\n\r", gyroBias[0]);
onehorse 0:2e5e65a6fb30 98 pc.printf("y gyro bias = %f\n\r", gyroBias[1]);
onehorse 0:2e5e65a6fb30 99 pc.printf("z gyro bias = %f\n\r", gyroBias[2]);
onehorse 0:2e5e65a6fb30 100 pc.printf("x accel bias = %f\n\r", accelBias[0]);
onehorse 0:2e5e65a6fb30 101 pc.printf("y accel bias = %f\n\r", accelBias[1]);
onehorse 0:2e5e65a6fb30 102 pc.printf("z accel bias = %f\n\r", accelBias[2]);
onehorse 0:2e5e65a6fb30 103 wait(2);
onehorse 0:2e5e65a6fb30 104 mpu9250.initMPU9250();
onehorse 0:2e5e65a6fb30 105 pc.printf("MPU9250 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature
onehorse 0:2e5e65a6fb30 106 mpu9250.initAK8963(magCalibration);
onehorse 0:2e5e65a6fb30 107 pc.printf("AK8963 initialized for active data mode....\n\r"); // Initialize device for active mode read of magnetometer
onehorse 0:2e5e65a6fb30 108 pc.printf("Accelerometer full-scale range = %f g\n\r", 2.0f*(float)(1<<Ascale));
onehorse 0:2e5e65a6fb30 109 pc.printf("Gyroscope full-scale range = %f deg/s\n\r", 250.0f*(float)(1<<Gscale));
onehorse 0:2e5e65a6fb30 110 if(Mscale == 0) pc.printf("Magnetometer resolution = 14 bits\n\r");
onehorse 0:2e5e65a6fb30 111 if(Mscale == 1) pc.printf("Magnetometer resolution = 16 bits\n\r");
onehorse 0:2e5e65a6fb30 112 if(Mmode == 2) pc.printf("Magnetometer ODR = 8 Hz\n\r");
onehorse 0:2e5e65a6fb30 113 if(Mmode == 6) pc.printf("Magnetometer ODR = 100 Hz\n\r");
onehorse 0:2e5e65a6fb30 114 wait(1);
onehorse 0:2e5e65a6fb30 115 }
onehorse 0:2e5e65a6fb30 116 else
onehorse 0:2e5e65a6fb30 117 {
onehorse 0:2e5e65a6fb30 118 pc.printf("Could not connect to MPU9250: \n\r");
onehorse 0:2e5e65a6fb30 119 pc.printf("%#x \n", whoami);
onehorse 0:2e5e65a6fb30 120
onehorse 0:2e5e65a6fb30 121 lcd.clear();
onehorse 0:2e5e65a6fb30 122 lcd.printString("MPU9250", 0, 0);
onehorse 0:2e5e65a6fb30 123 lcd.printString("no connection", 0, 1);
onehorse 0:2e5e65a6fb30 124 sprintf(buffer, "WHO_AM_I 0x%x", whoami);
onehorse 0:2e5e65a6fb30 125 lcd.printString(buffer, 0, 2);
onehorse 0:2e5e65a6fb30 126
onehorse 0:2e5e65a6fb30 127 while(1) ; // Loop forever if communication doesn't happen
onehorse 0:2e5e65a6fb30 128 }
onehorse 0:2e5e65a6fb30 129
onehorse 0:2e5e65a6fb30 130 mpu9250.getAres(); // Get accelerometer sensitivity
onehorse 0:2e5e65a6fb30 131 mpu9250.getGres(); // Get gyro sensitivity
onehorse 0:2e5e65a6fb30 132 mpu9250.getMres(); // Get magnetometer sensitivity
onehorse 0:2e5e65a6fb30 133 pc.printf("Accelerometer sensitivity is %f LSB/g \n\r", 1.0f/aRes);
onehorse 0:2e5e65a6fb30 134 pc.printf("Gyroscope sensitivity is %f LSB/deg/s \n\r", 1.0f/gRes);
onehorse 0:2e5e65a6fb30 135 pc.printf("Magnetometer sensitivity is %f LSB/G \n\r", 1.0f/mRes);
onehorse 0:2e5e65a6fb30 136 magbias[0] = +470.; // User environmental x-axis correction in milliGauss, should be automatically calculated
onehorse 0:2e5e65a6fb30 137 magbias[1] = +120.; // User environmental x-axis correction in milliGauss
onehorse 0:2e5e65a6fb30 138 magbias[2] = +125.; // User environmental x-axis correction in milliGauss
onehorse 0:2e5e65a6fb30 139
onehorse 0:2e5e65a6fb30 140 while(1) {
onehorse 0:2e5e65a6fb30 141
onehorse 0:2e5e65a6fb30 142 // If intPin goes high, all data registers have new data
onehorse 0:2e5e65a6fb30 143 if(mpu9250.readByte(MPU9250_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt
onehorse 0:2e5e65a6fb30 144
onehorse 0:2e5e65a6fb30 145 mpu9250.readAccelData(accelCount); // Read the x/y/z adc values
onehorse 0:2e5e65a6fb30 146 // Now we'll calculate the accleration value into actual g's
onehorse 0:2e5e65a6fb30 147 ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set
onehorse 0:2e5e65a6fb30 148 ay = (float)accelCount[1]*aRes - accelBias[1];
onehorse 0:2e5e65a6fb30 149 az = (float)accelCount[2]*aRes - accelBias[2];
onehorse 0:2e5e65a6fb30 150
onehorse 0:2e5e65a6fb30 151 mpu9250.readGyroData(gyroCount); // Read the x/y/z adc values
onehorse 0:2e5e65a6fb30 152 // Calculate the gyro value into actual degrees per second
onehorse 0:2e5e65a6fb30 153 gx = (float)gyroCount[0]*gRes - gyroBias[0]; // get actual gyro value, this depends on scale being set
onehorse 0:2e5e65a6fb30 154 gy = (float)gyroCount[1]*gRes - gyroBias[1];
onehorse 0:2e5e65a6fb30 155 gz = (float)gyroCount[2]*gRes - gyroBias[2];
onehorse 0:2e5e65a6fb30 156
onehorse 0:2e5e65a6fb30 157 mpu9250.readMagData(magCount); // Read the x/y/z adc values
onehorse 0:2e5e65a6fb30 158 // Calculate the magnetometer values in milliGauss
onehorse 0:2e5e65a6fb30 159 // Include factory calibration per data sheet and user environmental corrections
onehorse 0:2e5e65a6fb30 160 mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0]; // get actual magnetometer value, this depends on scale being set
onehorse 0:2e5e65a6fb30 161 my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1];
onehorse 0:2e5e65a6fb30 162 mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2];
onehorse 0:2e5e65a6fb30 163 }
onehorse 0:2e5e65a6fb30 164
onehorse 0:2e5e65a6fb30 165 Now = t.read_us();
onehorse 0:2e5e65a6fb30 166 deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update
onehorse 0:2e5e65a6fb30 167 lastUpdate = Now;
onehorse 0:2e5e65a6fb30 168
onehorse 0:2e5e65a6fb30 169 sum += deltat;
onehorse 0:2e5e65a6fb30 170 sumCount++;
onehorse 0:2e5e65a6fb30 171
onehorse 0:2e5e65a6fb30 172 // if(lastUpdate - firstUpdate > 10000000.0f) {
onehorse 0:2e5e65a6fb30 173 // beta = 0.04; // decrease filter gain after stabilized
onehorse 0:2e5e65a6fb30 174 // zeta = 0.015; // increasey bias drift gain after stabilized
onehorse 0:2e5e65a6fb30 175 // }
onehorse 0:2e5e65a6fb30 176
onehorse 0:2e5e65a6fb30 177 // Pass gyro rate as rad/s
onehorse 0:2e5e65a6fb30 178 // mpu9250.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
onehorse 0:2e5e65a6fb30 179 mpu9250.MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
onehorse 0:2e5e65a6fb30 180
onehorse 0:2e5e65a6fb30 181 // Serial print and/or display at 0.5 s rate independent of data rates
onehorse 0:2e5e65a6fb30 182 delt_t = t.read_ms() - count;
onehorse 0:2e5e65a6fb30 183 if (delt_t > 500) { // update LCD once per half-second independent of read rate
onehorse 0:2e5e65a6fb30 184
onehorse 0:2e5e65a6fb30 185 pc.printf("ax = %f", 1000*ax);
onehorse 0:2e5e65a6fb30 186 pc.printf(" ay = %f", 1000*ay);
onehorse 0:2e5e65a6fb30 187 pc.printf(" az = %f mg\n\r", 1000*az);
onehorse 0:2e5e65a6fb30 188
onehorse 0:2e5e65a6fb30 189 pc.printf("gx = %f", gx);
onehorse 0:2e5e65a6fb30 190 pc.printf(" gy = %f", gy);
onehorse 0:2e5e65a6fb30 191 pc.printf(" gz = %f deg/s\n\r", gz);
onehorse 0:2e5e65a6fb30 192
onehorse 0:2e5e65a6fb30 193 pc.printf("gx = %f", mx);
onehorse 0:2e5e65a6fb30 194 pc.printf(" gy = %f", my);
onehorse 0:2e5e65a6fb30 195 pc.printf(" gz = %f mG\n\r", mz);
onehorse 0:2e5e65a6fb30 196
onehorse 0:2e5e65a6fb30 197 tempCount = mpu9250.readTempData(); // Read the adc values
onehorse 0:2e5e65a6fb30 198 temperature = ((float) tempCount) / 333.87f + 21.0f; // Temperature in degrees Centigrade
onehorse 0:2e5e65a6fb30 199 pc.printf(" temperature = %f C\n\r", temperature);
onehorse 0:2e5e65a6fb30 200
onehorse 0:2e5e65a6fb30 201 pc.printf("q0 = %f\n\r", q[0]);
onehorse 0:2e5e65a6fb30 202 pc.printf("q1 = %f\n\r", q[1]);
onehorse 0:2e5e65a6fb30 203 pc.printf("q2 = %f\n\r", q[2]);
onehorse 0:2e5e65a6fb30 204 pc.printf("q3 = %f\n\r", q[3]);
onehorse 0:2e5e65a6fb30 205
onehorse 0:2e5e65a6fb30 206 /* lcd.clear();
onehorse 0:2e5e65a6fb30 207 lcd.printString("MPU9250", 0, 0);
onehorse 0:2e5e65a6fb30 208 lcd.printString("x y z", 0, 1);
onehorse 0:2e5e65a6fb30 209 sprintf(buffer, "%d %d %d mg", (int)(1000.0f*ax), (int)(1000.0f*ay), (int)(1000.0f*az));
onehorse 0:2e5e65a6fb30 210 lcd.printString(buffer, 0, 2);
onehorse 0:2e5e65a6fb30 211 sprintf(buffer, "%d %d %d deg/s", (int)gx, (int)gy, (int)gz);
onehorse 0:2e5e65a6fb30 212 lcd.printString(buffer, 0, 3);
onehorse 0:2e5e65a6fb30 213 sprintf(buffer, "%d %d %d mG", (int)mx, (int)my, (int)mz);
onehorse 0:2e5e65a6fb30 214 lcd.printString(buffer, 0, 4);
onehorse 0:2e5e65a6fb30 215 */
onehorse 0:2e5e65a6fb30 216 // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation.
onehorse 0:2e5e65a6fb30 217 // In this coordinate system, the positive z-axis is down toward Earth.
onehorse 0:2e5e65a6fb30 218 // 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.
onehorse 0:2e5e65a6fb30 219 // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative.
onehorse 0:2e5e65a6fb30 220 // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll.
onehorse 0:2e5e65a6fb30 221 // These arise from the definition of the homogeneous rotation matrix constructed from quaternions.
onehorse 0:2e5e65a6fb30 222 // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be
onehorse 0:2e5e65a6fb30 223 // applied in the correct order which for this configuration is yaw, pitch, and then roll.
onehorse 0:2e5e65a6fb30 224 // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links.
onehorse 0:2e5e65a6fb30 225 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]);
onehorse 0:2e5e65a6fb30 226 pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
onehorse 0:2e5e65a6fb30 227 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]);
onehorse 0:2e5e65a6fb30 228 pitch *= 180.0f / PI;
onehorse 0:2e5e65a6fb30 229 yaw *= 180.0f / PI;
onehorse 0:2e5e65a6fb30 230 yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04
onehorse 0:2e5e65a6fb30 231 roll *= 180.0f / PI;
onehorse 0:2e5e65a6fb30 232
onehorse 0:2e5e65a6fb30 233 pc.printf("Yaw, Pitch, Roll: %f %f %f\n\r", yaw, pitch, roll);
onehorse 0:2e5e65a6fb30 234 pc.printf("average rate = %f\n\r", (float) sumCount/sum);
onehorse 0:2e5e65a6fb30 235 // sprintf(buffer, "YPR: %f %f %f", yaw, pitch, roll);
onehorse 0:2e5e65a6fb30 236 // lcd.printString(buffer, 0, 4);
onehorse 0:2e5e65a6fb30 237 // sprintf(buffer, "rate = %f", (float) sumCount/sum);
onehorse 0:2e5e65a6fb30 238 // lcd.printString(buffer, 0, 5);
onehorse 0:2e5e65a6fb30 239
onehorse 0:2e5e65a6fb30 240 myled= !myled;
onehorse 0:2e5e65a6fb30 241 count = t.read_ms();
onehorse 0:2e5e65a6fb30 242
onehorse 0:2e5e65a6fb30 243 if(count > 1<<21) {
onehorse 0:2e5e65a6fb30 244 t.start(); // start the timer over again if ~30 minutes has passed
onehorse 0:2e5e65a6fb30 245 count = 0;
onehorse 0:2e5e65a6fb30 246 deltat= 0;
onehorse 0:2e5e65a6fb30 247 lastUpdate = t.read_us();
onehorse 0:2e5e65a6fb30 248 }
onehorse 0:2e5e65a6fb30 249 sum = 0;
onehorse 0:2e5e65a6fb30 250 sumCount = 0;
onehorse 0:2e5e65a6fb30 251 }
onehorse 0:2e5e65a6fb30 252 }
onehorse 0:2e5e65a6fb30 253
onehorse 0:2e5e65a6fb30 254 }