PES4 / Mbed OS Queue_02
Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers MPU9250.cpp Source File

MPU9250.cpp

00001 #include "MPU9250.h"
00002 
00003 
00004 
00005 uint8_t Ascale = AFS_2G;     // AFS_2G, AFS_4G, AFS_8G, AFS_16G
00006 uint8_t Gscale = GFS_250DPS; // GFS_250DPS, GFS_500DPS, GFS_1000DPS, GFS_2000DPS
00007 uint8_t Mscale = MFS_16BITS; // MFS_14BITS or MFS_16BITS, 14-bit or 16-bit magnetometer resolution
00008 uint8_t Mmode = 0x06;        // Either 8 Hz 0x02) or 100 Hz (0x06) magnetometer data ODR
00009 float aRes, gRes, mRes;      // scale resolutions per LSB for the sensors
00010 
00011 //Set up I2C, (SDA,SCL)
00012 I2C i2c(PB_9, PB_8);
00013 
00014 DigitalOut myled(LED1);
00015 
00016 // Pin definitions
00017 int intPin = 12;  // These can be changed, 2 and 3 are the Arduinos ext int pins
00018 
00019 int16_t accelCount[3];  // Stores the 16-bit signed accelerometer sensor output
00020 int16_t gyroCount[3];   // Stores the 16-bit signed gyro sensor output
00021 int16_t magCount[3];    // Stores the 16-bit signed magnetometer sensor output
00022 float magCalibration[3] = {0, 0, 0}, magbias[3] = {0, 0, 0};  // Factory mag calibration and mag bias
00023 float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer
00024 float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values
00025 int16_t tempCount;   // Stores the real internal chip temperature in degrees Celsius
00026 float temperature;
00027 float SelfTest[6];
00028 
00029 int delt_t = 0; // used to control display output rate
00030 int _count = 0;  // used to control display output rate
00031 
00032 // parameters for 6 DoF sensor fusion calculations
00033 float PI = 3.14159265358979323846f;
00034 float GyroMeasError = PI * (60.0f / 180.0f);     // gyroscope measurement error in rads/s (start at 60 deg/s), then reduce after ~10 s to 3
00035 float beta = sqrt(3.0f / 4.0f) * GyroMeasError;  // compute beta
00036 float GyroMeasDrift = PI * (1.0f / 180.0f);      // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s)
00037 float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift;  // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value
00038 #define Kp 2.0f * 5.0f // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral
00039 #define Ki 0.0f
00040 
00041 float pitch, yaw, roll;
00042 float vx, vy, vz;
00043 float deltat = 0.0f;                             // integration interval for both filter schemes
00044 int lastUpdate = 0, firstUpdate = 0, Now = 0;    // used to calculate integration interval                               // used to calculate integration interval
00045 float q[4] = {1.0f, 0.0f, 0.0f, 0.0f};           // vector to hold quaternion
00046 float v_trans[3] = {0.0f, 0.0f, 0.0f};                 // vector to hold translative velocities
00047 float a_old[3] = {0.00f, 0.00f, 0.00f};
00048 float eInt[3] = {0.0f, 0.0f, 0.0f};              // vector to hold integral error for Mahony method
00049 
00050 
00051 accData_t myData;
00052 MPU9250 mpu9250;
00053 Timer t;
00054 Serial pc(USBTX, USBRX); // tx, rx
00055 
00056 #define SAMPLE_TIME 100
00057 
00058 
00059 float sum = 0;
00060 uint32_t sumCount = 0;
00061 char buffer[14];
00062 
00063 
00064 //===================================================================================================================
00065 //====== Set of useful function to access acceleratio, gyroscope, and temperature data
00066 //===================================================================================================================
00067 
00068 void MPU9250::writeByte(uint8_t address, uint8_t subAddress, uint8_t data)
00069 {
00070     char data_write[2];
00071     data_write[0] = subAddress;
00072     data_write[1] = data;
00073     i2c.write(address, data_write, 2, 0);
00074 }
00075 
00076 char MPU9250::readByte(uint8_t address, uint8_t subAddress)
00077 {
00078     char data[1]; // `data` will store the register data
00079     char data_write[1];
00080     data_write[0] = subAddress;
00081     i2c.write(address, data_write, 1, 1); // no stop
00082     i2c.read(address, data, 1, 0);
00083     return data[0];
00084 }
00085 
00086 void MPU9250::readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest)
00087 {
00088     char data[14];
00089     char data_write[1];
00090     data_write[0] = subAddress;
00091     i2c.write(address, data_write, 1, 1); // no stop
00092     i2c.read(address, data, count, 0);
00093     for(int ii = 0; ii < count; ii++) {
00094         dest[ii] = data[ii];
00095     }
00096 }
00097 
00098 
00099 void MPU9250::getMres()
00100 {
00101     switch (Mscale) {
00102         // Possible magnetometer scales (and their register bit settings) are:
00103         // 14 bit resolution (0) and 16 bit resolution (1)
00104         case MFS_14BITS:
00105             mRes = 10.0*4219.0/8190.0; // Proper scale to return milliGauss
00106             break;
00107         case MFS_16BITS:
00108             mRes = 10.0*4219.0/32760.0; // Proper scale to return milliGauss
00109             break;
00110     }
00111 }
00112 
00113 
00114 void MPU9250::getGres()
00115 {
00116     switch (Gscale) {
00117         // Possible gyro scales (and their register bit settings) are:
00118         // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS  (11).
00119         // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
00120         case GFS_250DPS:
00121             gRes = 250.0/32768.0;
00122             break;
00123         case GFS_500DPS:
00124             gRes = 500.0/32768.0;
00125             break;
00126         case GFS_1000DPS:
00127             gRes = 1000.0/32768.0;
00128             break;
00129         case GFS_2000DPS:
00130             gRes = 2000.0/32768.0;
00131             break;
00132     }
00133 }
00134 
00135 
00136 void MPU9250::getAres()
00137 {
00138     switch (Ascale) {
00139         // Possible accelerometer scales (and their register bit settings) are:
00140         // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs  (11).
00141         // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
00142         case AFS_2G:
00143             aRes = 2.0/32768.0;
00144             break;
00145         case AFS_4G:
00146             aRes = 4.0/32768.0;
00147             break;
00148         case AFS_8G:
00149             aRes = 8.0/32768.0;
00150             break;
00151         case AFS_16G:
00152             aRes = 16.0/32768.0;
00153             break;
00154     }
00155 }
00156 
00157 
00158 void MPU9250::readAccelData(int16_t * destination)
00159 {
00160     uint8_t rawData[6];  // x/y/z accel register data stored here
00161     readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]);  // Read the six raw data registers into data array
00162     destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ;  // Turn the MSB and LSB into a signed 16-bit value
00163     destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
00164     destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
00165 }
00166 
00167 void MPU9250::readGyroData(int16_t * destination)
00168 {
00169     uint8_t rawData[6];  // x/y/z gyro register data stored here
00170     readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]);  // Read the six raw data registers sequentially into data array
00171     destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ;  // Turn the MSB and LSB into a signed 16-bit value
00172     destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
00173     destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
00174 }
00175 
00176 void MPU9250::readMagData(int16_t * destination)
00177 {
00178     uint8_t rawData[7];  // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition
00179     if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // wait for magnetometer data ready bit to be set
00180         readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]);  // Read the six raw data and ST2 registers sequentially into data array
00181         uint8_t c = rawData[6]; // End data read by reading ST2 register
00182         if(!(c & 0x08)) { // Check if magnetic sensor overflow set, if not then report data
00183             destination[0] = (int16_t)(((int16_t)rawData[1] << 8) | rawData[0]);  // Turn the MSB and LSB into a signed 16-bit value
00184             destination[1] = (int16_t)(((int16_t)rawData[3] << 8) | rawData[2]) ;  // Data stored as little Endian
00185             destination[2] = (int16_t)(((int16_t)rawData[5] << 8) | rawData[4]) ;
00186         }
00187     }
00188 }
00189 
00190 int16_t MPU9250::readTempData()
00191 {
00192     uint8_t rawData[2];  // x/y/z gyro register data stored here
00193     readBytes(MPU9250_ADDRESS, TEMP_OUT_H, 2, &rawData[0]);  // Read the two raw data registers sequentially into data array
00194     return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ;  // Turn the MSB and LSB into a 16-bit value
00195 }
00196 
00197 
00198 void MPU9250::resetMPU9250()
00199 {
00200     // reset device
00201     writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
00202     wait(0.1);
00203 }
00204 
00205 void MPU9250::initAK8963(float * destination)
00206 {
00207     // First extract the factory calibration for each magnetometer axis
00208     uint8_t rawData[3];  // x/y/z gyro calibration data stored here
00209     writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer
00210     wait(0.01);
00211     writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode
00212     wait(0.01);
00213     readBytes(AK8963_ADDRESS, AK8963_ASAX, 3, &rawData[0]);  // Read the x-, y-, and z-axis calibration values
00214     destination[0] =  (float)(rawData[0] - 128)/256.0f + 1.0f;   // Return x-axis sensitivity adjustment values, etc.
00215     destination[1] =  (float)(rawData[1] - 128)/256.0f + 1.0f;
00216     destination[2] =  (float)(rawData[2] - 128)/256.0f + 1.0f;
00217     writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer
00218     wait(0.01);
00219     // Configure the magnetometer for continuous read and highest resolution
00220     // set Mscale bit 4 to 1 (0) to enable 16 (14) bit resolution in CNTL register,
00221     // and enable continuous mode data acquisition Mmode (bits [3:0]), 0010 for 8 Hz and 0110 for 100 Hz sample rates
00222     writeByte(AK8963_ADDRESS, AK8963_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR
00223     wait(0.01);
00224 }
00225 
00226 
00227 void MPU9250::initMPU9250()
00228 {
00229 // Initialize MPU9250 device
00230 // wake up device
00231     writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors
00232     wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt
00233 
00234 // get stable time source
00235     writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01);  // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
00236 
00237 // Configure Gyro and Accelerometer
00238 // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively;
00239 // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both
00240 // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate
00241     writeByte(MPU9250_ADDRESS, CONFIG, 0x03);
00242 
00243 // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV)
00244     writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x04);  // Use a 200 Hz rate; the same rate set in CONFIG above
00245 
00246 // Set gyroscope full scale range
00247 // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3
00248     uint8_t c =  readByte(MPU9250_ADDRESS, GYRO_CONFIG);
00249     writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5]
00250     writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3]
00251     writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro
00252 
00253 // Set accelerometer configuration
00254     c =  readByte(MPU9250_ADDRESS, ACCEL_CONFIG);
00255     writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5]
00256     writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3]
00257     writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer
00258 
00259 // Set accelerometer sample rate configuration
00260 // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for
00261 // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz
00262     c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2);
00263     writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c & ~0x0F); // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0])
00264     writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c | 0x03); // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz
00265 
00266 // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates,
00267 // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting
00268 
00269     // Configure Interrupts and Bypass Enable
00270     // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips
00271     // can join the I2C bus and all can be controlled by the Arduino as master
00272     writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22);
00273     writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01);  // Enable data ready (bit 0) interrupt
00274 }
00275 
00276 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average
00277 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers.
00278 void MPU9250::calibrateMPU9250(float * dest1, float * dest2)
00279 {
00280     uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data
00281     uint16_t ii, packet_count, fifo_count;
00282     int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0};
00283 
00284 // reset device, reset all registers, clear gyro and accelerometer bias registers
00285     writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
00286     wait(0.1);
00287 
00288 // get stable time source
00289 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
00290     writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01);
00291     writeByte(MPU9250_ADDRESS, PWR_MGMT_2, 0x00);
00292     wait(0.2);
00293 
00294 // Configure device for bias calculation
00295     writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x00);   // Disable all interrupts
00296     writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00);      // Disable FIFO
00297     writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00);   // Turn on internal clock source
00298     writeByte(MPU9250_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master
00299     writeByte(MPU9250_ADDRESS, USER_CTRL, 0x00);    // Disable FIFO and I2C master modes
00300     writeByte(MPU9250_ADDRESS, USER_CTRL, 0x0C);    // Reset FIFO and DMP
00301     wait(0.015);
00302 
00303 // Configure MPU9250 gyro and accelerometer for bias calculation
00304     writeByte(MPU9250_ADDRESS, CONFIG, 0x01);      // Set low-pass filter to 188 Hz
00305     writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00);  // Set sample rate to 1 kHz
00306     writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00);  // Set gyro full-scale to 250 degrees per second, maximum sensitivity
00307     writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity
00308 
00309     uint16_t  gyrosensitivity  = 131;   // = 131 LSB/degrees/sec
00310     uint16_t  accelsensitivity = 16384;  // = 16384 LSB/g
00311 
00312 // Configure FIFO to capture accelerometer and gyro data for bias calculation
00313     writeByte(MPU9250_ADDRESS, USER_CTRL, 0x40);   // Enable FIFO
00314     writeByte(MPU9250_ADDRESS, FIFO_EN, 0x78);     // Enable gyro and accelerometer sensors for FIFO (max size 512 bytes in MPU-9250)
00315     wait(0.04); // accumulate 40 samples in 80 milliseconds = 480 bytes
00316 
00317 // At end of sample accumulation, turn off FIFO sensor read
00318     writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00);        // Disable gyro and accelerometer sensors for FIFO
00319     readBytes(MPU9250_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count
00320     fifo_count = ((uint16_t)data[0] << 8) | data[1];
00321     packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging
00322 
00323     for (ii = 0; ii < packet_count; ii++) {
00324         int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0};
00325         readBytes(MPU9250_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging
00326         accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1]  ) ;  // Form signed 16-bit integer for each sample in FIFO
00327         accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3]  ) ;
00328         accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5]  ) ;
00329         gyro_temp[0]  = (int16_t) (((int16_t)data[6] << 8) | data[7]  ) ;
00330         gyro_temp[1]  = (int16_t) (((int16_t)data[8] << 8) | data[9]  ) ;
00331         gyro_temp[2]  = (int16_t) (((int16_t)data[10] << 8) | data[11]) ;
00332 
00333         accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases
00334         accel_bias[1] += (int32_t) accel_temp[1];
00335         accel_bias[2] += (int32_t) accel_temp[2];
00336         gyro_bias[0]  += (int32_t) gyro_temp[0];
00337         gyro_bias[1]  += (int32_t) gyro_temp[1];
00338         gyro_bias[2]  += (int32_t) gyro_temp[2];
00339 
00340     }
00341     accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases
00342     accel_bias[1] /= (int32_t) packet_count;
00343     accel_bias[2] /= (int32_t) packet_count;
00344     gyro_bias[0]  /= (int32_t) packet_count;
00345     gyro_bias[1]  /= (int32_t) packet_count;
00346     gyro_bias[2]  /= (int32_t) packet_count;
00347 
00348     if(accel_bias[2] > 0L) {
00349         accel_bias[2] -= (int32_t) accelsensitivity;   // Remove gravity from the z-axis accelerometer bias calculation
00350     } else {
00351         accel_bias[2] += (int32_t) accelsensitivity;
00352     }
00353 
00354 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup
00355     data[0] = (-gyro_bias[0]/4  >> 8) & 0xFF; // Divide by 4 to get 32.9 LSB per deg/s to conform to expected bias input format
00356     data[1] = (-gyro_bias[0]/4)       & 0xFF; // Biases are additive, so change sign on calculated average gyro biases
00357     data[2] = (-gyro_bias[1]/4  >> 8) & 0xFF;
00358     data[3] = (-gyro_bias[1]/4)       & 0xFF;
00359     data[4] = (-gyro_bias[2]/4  >> 8) & 0xFF;
00360     data[5] = (-gyro_bias[2]/4)       & 0xFF;
00361 
00362 /// Push gyro biases to hardware registers
00363     /*  writeByte(MPU9250_ADDRESS, XG_OFFSET_H, data[0]);
00364       writeByte(MPU9250_ADDRESS, XG_OFFSET_L, data[1]);
00365       writeByte(MPU9250_ADDRESS, YG_OFFSET_H, data[2]);
00366       writeByte(MPU9250_ADDRESS, YG_OFFSET_L, data[3]);
00367       writeByte(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]);
00368       writeByte(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]);
00369     */
00370     dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction
00371     dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity;
00372     dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity;
00373 
00374 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain
00375 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold
00376 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature
00377 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that
00378 // the accelerometer biases calculated above must be divided by 8.
00379 
00380     int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases
00381     readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values
00382     accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1];
00383     readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]);
00384     accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1];
00385     readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]);
00386     accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1];
00387 
00388     uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers
00389     uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis
00390 
00391     for(ii = 0; ii < 3; ii++) {
00392         if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit
00393     }
00394 
00395     // Construct total accelerometer bias, including calculated average accelerometer bias from above
00396     accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale)
00397     accel_bias_reg[1] -= (accel_bias[1]/8);
00398     accel_bias_reg[2] -= (accel_bias[2]/8);
00399 
00400     data[0] = (accel_bias_reg[0] >> 8) & 0xFF;
00401     data[1] = (accel_bias_reg[0])      & 0xFF;
00402     data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers
00403     data[2] = (accel_bias_reg[1] >> 8) & 0xFF;
00404     data[3] = (accel_bias_reg[1])      & 0xFF;
00405     data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers
00406     data[4] = (accel_bias_reg[2] >> 8) & 0xFF;
00407     data[5] = (accel_bias_reg[2])      & 0xFF;
00408     data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers
00409 
00410 // Apparently this is not working for the acceleration biases in the MPU-9250
00411 // Are we handling the temperature correction bit properly?
00412 // Push accelerometer biases to hardware registers
00413     /*  writeByte(MPU9250_ADDRESS, XA_OFFSET_H, data[0]);
00414       writeByte(MPU9250_ADDRESS, XA_OFFSET_L, data[1]);
00415       writeByte(MPU9250_ADDRESS, YA_OFFSET_H, data[2]);
00416       writeByte(MPU9250_ADDRESS, YA_OFFSET_L, data[3]);
00417       writeByte(MPU9250_ADDRESS, ZA_OFFSET_H, data[4]);
00418       writeByte(MPU9250_ADDRESS, ZA_OFFSET_L, data[5]);
00419     */
00420 // Output scaled accelerometer biases for manual subtraction in the main program
00421     dest2[0] = (float)accel_bias[0]/(float)accelsensitivity;
00422     dest2[1] = (float)accel_bias[1]/(float)accelsensitivity;
00423     dest2[2] = (float)accel_bias[2]/(float)accelsensitivity;
00424 }
00425 
00426 
00427 // Accelerometer and gyroscope self test; check calibration wrt factory settings
00428 void MPU9250::MPU9250SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass
00429 {
00430     uint8_t rawData[6] = {0, 0, 0, 0, 0, 0};
00431     uint8_t selfTest[6];
00432     int16_t gAvg[3], aAvg[3], aSTAvg[3], gSTAvg[3];
00433     float factoryTrim[6];
00434     uint8_t FS = 0;
00435 
00436     writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz
00437     writeByte(MPU9250_ADDRESS, CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz
00438     writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 1<<FS); // Set full scale range for the gyro to 250 dps
00439     writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz
00440     writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 1<<FS); // Set full scale range for the accelerometer to 2 g
00441 
00442     for( int ii = 0; ii < 200; ii++) { // get average current values of gyro and acclerometer
00443 
00444         readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
00445         aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
00446         aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
00447         aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
00448 
00449         readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
00450         gAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
00451         gAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
00452         gAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
00453     }
00454 
00455     for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average current readings
00456         aAvg[ii] /= 200;
00457         gAvg[ii] /= 200;
00458     }
00459 
00460 // Configure the accelerometer for self-test
00461     writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g
00462     writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s
00463     wait(0.025); // Delay a while to let the device stabilize
00464 
00465     for( int ii = 0; ii < 200; ii++) { // get average self-test values of gyro and acclerometer
00466 
00467         readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
00468         aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
00469         aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
00470         aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
00471 
00472         readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
00473         gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
00474         gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
00475         gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
00476     }
00477 
00478     for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average self-test readings
00479         aSTAvg[ii] /= 200;
00480         gSTAvg[ii] /= 200;
00481     }
00482 
00483 // Configure the gyro and accelerometer for normal operation
00484     writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00);
00485     writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00);
00486     wait(0.025); // Delay a while to let the device stabilize
00487 
00488     // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg
00489     selfTest[0] = readByte(MPU9250_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results
00490     selfTest[1] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_ACCEL); // Y-axis accel self-test results
00491     selfTest[2] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_ACCEL); // Z-axis accel self-test results
00492     selfTest[3] = readByte(MPU9250_ADDRESS, SELF_TEST_X_GYRO); // X-axis gyro self-test results
00493     selfTest[4] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_GYRO); // Y-axis gyro self-test results
00494     selfTest[5] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_GYRO); // Z-axis gyro self-test results
00495 
00496     // Retrieve factory self-test value from self-test code reads
00497     factoryTrim[0] = (float)(2620/1<<FS)*(pow( 1.01, ((float)selfTest[0] - 1.0) ));  // FT[Xa] factory trim calculation
00498     factoryTrim[1] = (float)(2620/1<<FS)*(pow( 1.01, ((float)selfTest[1] - 1.0) ));  // FT[Ya] factory trim calculation
00499     factoryTrim[2] = (float)(2620/1<<FS)*(pow( 1.01, ((float)selfTest[2] - 1.0) ));  // FT[Za] factory trim calculation
00500     factoryTrim[3] = (float)(2620/1<<FS)*(pow( 1.01, ((float)selfTest[3] - 1.0) ));  // FT[Xg] factory trim calculation
00501     factoryTrim[4] = (float)(2620/1<<FS)*(pow( 1.01, ((float)selfTest[4] - 1.0) ));  // FT[Yg] factory trim calculation
00502     factoryTrim[5] = (float)(2620/1<<FS)*(pow( 1.01, ((float)selfTest[5] - 1.0) ));  // FT[Zg] factory trim calculation
00503 
00504 // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response
00505 // To get percent, must multiply by 100
00506     for (int i = 0; i < 3; i++) {
00507         destination[i] = 100.0*((float)(aSTAvg[i] - aAvg[i]))/factoryTrim[i]; // Report percent differences
00508         destination[i+3] = 100.0*((float)(gSTAvg[i] - gAvg[i]))/factoryTrim[i+3]; // Report percent differences
00509     }
00510 
00511 }
00512 
00513 
00514 
00515 // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays"
00516 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details)
00517 // which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute
00518 // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc.
00519 // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms
00520 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz!
00521 void MPU9250::MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
00522 {
00523     float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3];   // short name local variable for readability
00524     float norm;
00525     float hx, hy, _2bx, _2bz;
00526     float s1, s2, s3, s4;
00527     float qDot1, qDot2, qDot3, qDot4;
00528 
00529     // Auxiliary variables to avoid repeated arithmetic
00530     float _2q1mx;
00531     float _2q1my;
00532     float _2q1mz;
00533     float _2q2mx;
00534     float _4bx;
00535     float _4bz;
00536     float _2q1 = 2.0f * q1;
00537     float _2q2 = 2.0f * q2;
00538     float _2q3 = 2.0f * q3;
00539     float _2q4 = 2.0f * q4;
00540     float _2q1q3 = 2.0f * q1 * q3;
00541     float _2q3q4 = 2.0f * q3 * q4;
00542     float q1q1 = q1 * q1;
00543     float q1q2 = q1 * q2;
00544     float q1q3 = q1 * q3;
00545     float q1q4 = q1 * q4;
00546     float q2q2 = q2 * q2;
00547     float q2q3 = q2 * q3;
00548     float q2q4 = q2 * q4;
00549     float q3q3 = q3 * q3;
00550     float q3q4 = q3 * q4;
00551     float q4q4 = q4 * q4;
00552 
00553     // Normalise accelerometer measurement
00554     norm = sqrt(ax * ax + ay * ay + az * az);
00555     if (norm == 0.0f) return; // handle NaN
00556     norm = 1.0f/norm;
00557     ax *= norm;
00558     ay *= norm;
00559     az *= norm;
00560 
00561     // Normalise magnetometer measurement
00562     norm = sqrt(mx * mx + my * my + mz * mz);
00563     if (norm == 0.0f) return; // handle NaN
00564     norm = 1.0f/norm;
00565     mx *= norm;
00566     my *= norm;
00567     mz *= norm;
00568 
00569     // Reference direction of Earth's magnetic field
00570     _2q1mx = 2.0f * q1 * mx;
00571     _2q1my = 2.0f * q1 * my;
00572     _2q1mz = 2.0f * q1 * mz;
00573     _2q2mx = 2.0f * q2 * mx;
00574     hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4;
00575     hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4;
00576     _2bx = sqrt(hx * hx + hy * hy);
00577     _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4;
00578     _4bx = 2.0f * _2bx;
00579     _4bz = 2.0f * _2bz;
00580 
00581     // Gradient decent algorithm corrective step
00582     s1 = -_2q3 * (2.0f * q2q4 - _2q1q3 - ax) + _2q2 * (2.0f * q1q2 + _2q3q4 - ay) - _2bz * q3 * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q4 + _2bz * q2) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + _2bx * q3 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz);
00583     s2 = _2q4 * (2.0f * q2q4 - _2q1q3 - ax) + _2q1 * (2.0f * q1q2 + _2q3q4 - ay) - 4.0f * q2 * (1.0f - 2.0f * q2q2 - 2.0f * q3q3 - az) + _2bz * q4 * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (_2bx * q3 + _2bz * q1) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + (_2bx * q4 - _4bz * q2) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz);
00584     s3 = -_2q1 * (2.0f * q2q4 - _2q1q3 - ax) + _2q4 * (2.0f * q1q2 + _2q3q4 - ay) - 4.0f * q3 * (1.0f - 2.0f * q2q2 - 2.0f * q3q3 - az) + (-_4bx * q3 - _2bz * q1) * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (_2bx * q2 + _2bz * q4) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + (_2bx * q1 - _4bz * q3) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz);
00585     s4 = _2q2 * (2.0f * q2q4 - _2q1q3 - ax) + _2q3 * (2.0f * q1q2 + _2q3q4 - ay) + (-_4bx * q4 + _2bz * q2) * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q1 + _2bz * q3) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + _2bx * q2 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz);
00586     norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4);    // normalise step magnitude
00587     norm = 1.0f/norm;
00588     s1 *= norm;
00589     s2 *= norm;
00590     s3 *= norm;
00591     s4 *= norm;
00592 
00593     // Compute rate of change of quaternion
00594     qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1;
00595     qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2;
00596     qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3;
00597     qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4;
00598 
00599     // Integrate to yield quaternion
00600     q1 += qDot1 * deltat;
00601     q2 += qDot2 * deltat;
00602     q3 += qDot3 * deltat;
00603     q4 += qDot4 * deltat;
00604     norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);    // normalise quaternion
00605     norm = 1.0f/norm;
00606     q[0] = q1 * norm;
00607     q[1] = q2 * norm;
00608     q[2] = q3 * norm;
00609     q[3] = q4 * norm;
00610 
00611 }
00612 
00613 
00614 
00615 // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and
00616 // measured ones.
00617 void MPU9250::MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
00618 {
00619     float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3];   // short name local variable for readability
00620     float norm;
00621     float hx, hy, bx, bz;
00622     float vx, vy, vz, wx, wy, wz;
00623     float ex, ey, ez;
00624     float pa, pb, pc;
00625 
00626     // Auxiliary variables to avoid repeated arithmetic
00627     float q1q1 = q1 * q1;
00628     float q1q2 = q1 * q2;
00629     float q1q3 = q1 * q3;
00630     float q1q4 = q1 * q4;
00631     float q2q2 = q2 * q2;
00632     float q2q3 = q2 * q3;
00633     float q2q4 = q2 * q4;
00634     float q3q3 = q3 * q3;
00635     float q3q4 = q3 * q4;
00636     float q4q4 = q4 * q4;
00637 
00638     // Normalise accelerometer measurement
00639     norm = sqrt(ax * ax + ay * ay + az * az);
00640     if (norm == 0.0f) return; // handle NaN
00641     norm = 1.0f / norm;        // use reciprocal for division
00642     ax *= norm;
00643     ay *= norm;
00644     az *= norm;
00645 
00646     // Normalise magnetometer measurement
00647     norm = sqrt(mx * mx + my * my + mz * mz);
00648     if (norm == 0.0f) return; // handle NaN
00649     norm = 1.0f / norm;        // use reciprocal for division
00650     mx *= norm;
00651     my *= norm;
00652     mz *= norm;
00653 
00654     // Reference direction of Earth's magnetic field
00655     hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3);
00656     hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2);
00657     bx = sqrt((hx * hx) + (hy * hy));
00658     bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3);
00659 
00660     // Estimated direction of gravity and magnetic field
00661     vx = 2.0f * (q2q4 - q1q3);
00662     vy = 2.0f * (q1q2 + q3q4);
00663     vz = q1q1 - q2q2 - q3q3 + q4q4;
00664     wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3);
00665     wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4);
00666     wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3);
00667 
00668     // Error is cross product between estimated direction and measured direction of gravity
00669     ex = (ay * vz - az * vy) + (my * wz - mz * wy);
00670     ey = (az * vx - ax * vz) + (mz * wx - mx * wz);
00671     ez = (ax * vy - ay * vx) + (mx * wy - my * wx);
00672     if (Ki > 0.0f) {
00673         eInt[0] += ex;      // accumulate integral error
00674         eInt[1] += ey;
00675         eInt[2] += ez;
00676     } else {
00677         eInt[0] = 0.0f;     // prevent integral wind up
00678         eInt[1] = 0.0f;
00679         eInt[2] = 0.0f;
00680     }
00681 
00682     // Apply feedback terms
00683     gx = gx + Kp * ex + Ki * eInt[0];
00684     gy = gy + Kp * ey + Ki * eInt[1];
00685     gz = gz + Kp * ez + Ki * eInt[2];
00686 
00687     // Integrate rate of change of quaternion
00688     pa = q2;
00689     pb = q3;
00690     pc = q4;
00691     q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat);
00692     q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat);
00693     q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat);
00694     q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat);
00695 
00696     // Normalise quaternion
00697     norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);
00698     norm = 1.0f / norm;
00699     q[0] = q1 * norm;
00700     q[1] = q2 * norm;
00701     q[2] = q3 * norm;
00702     q[3] = q4 * norm;
00703 
00704 }
00705 
00706 // Integrates the acceleration to get the boards translative velocity
00707 void MPU9250::velocityUpdate(float ax, float ay, float az)
00708 {
00709     // short name local variable for readability
00710 
00711     v_trans[0] = deltat*0.5*(a_old[0] + ax*GRAVITATION) + v_trans[0];
00712     v_trans[1] = deltat*0.5*(a_old[1] + ay*GRAVITATION) + v_trans[1];
00713     v_trans[2] = deltat*0.5*(a_old[2] + az*GRAVITATION + GRAVITATION) + v_trans[2];
00714 
00715     a_old[0] = ax*GRAVITATION;
00716     a_old[1] = ay*GRAVITATION;
00717     a_old[2] = az*GRAVITATION;
00718 }
00719 
00720 void MPU9250::readIMU()
00721 {
00722     // If intPin goes high, all data registers have new data
00723     if(mpu9250.readByte(MPU9250_ADDRESS, INT_STATUS) & 0x01) {  // On interrupt, check if data ready interrupt
00724 
00725         mpu9250.readAccelData(accelCount);  // Read the x/y/z adc values
00726         // Now we'll calculate the accleration value into actual g's
00727         ax = (float)accelCount[0]*aRes - accelBias[0];  // get actual g value, this depends on scale being set
00728         ay = (float)accelCount[1]*aRes - accelBias[1];
00729         az = (float)accelCount[2]*aRes - accelBias[2];
00730 
00731         mpu9250.readGyroData(gyroCount);  // Read the x/y/z adc values
00732         // Calculate the gyro value into actual degrees per second
00733         gx = (float)gyroCount[0]*gRes - gyroBias[0];  // get actual gyro value, this depends on scale being set
00734         gy = (float)gyroCount[1]*gRes - gyroBias[1];
00735         gz = (float)gyroCount[2]*gRes - gyroBias[2];
00736 
00737         mpu9250.readMagData(magCount);  // Read the x/y/z adc values
00738         // Calculate the magnetometer values in milliGauss
00739         // Include factory calibration per data sheet and user environmental corrections
00740         mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0];  // get actual magnetometer value, this depends on scale being set
00741         my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1];
00742         mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2];
00743     }
00744 
00745     pc.printf("ax, ay, az, delta_t;%f;%f;%f;%f\n\r", ax, ay, az*GRAVITATION + GRAVITATION, deltat);
00746 
00747     Now = t.read_us();
00748 
00749     deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update
00750     lastUpdate = Now;
00751 
00752     sum += deltat;
00753     sumCount++;
00754 
00755 
00756     mpu9250.velocityUpdate(ax, ay, az);
00757 
00758     // Pass gyro rate as rad/s
00759     mpu9250.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f,  my,  mx, mz);
00760     //mpu9250.MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
00761 
00762     // Serial print and/or display at 0.5 s rate independent of data rates
00763     delt_t = t.read_ms() - _count;
00764 
00765     //-----------------------------------------
00766     // Update displayed value
00767     if (delt_t > SAMPLE_TIME) {
00768 
00769 
00770 
00771         //pc.printf("vx, vy, vz: %f %f %f\n\r", v_trans[0], v_trans[1], v_trans[2]);
00772 
00773 
00774         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]);
00775         pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
00776         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]);
00777         pitch *= 180.0f / PI;
00778         yaw   *= 180.0f / PI;
00779         yaw   -= 2.93f; // Declination at 8572 Berg TG: +2° 56'
00780         roll  *= 180.0f / PI;
00781         
00782         myData.ax = yaw;
00783         myData.ay = pitch;
00784         myData.az = roll;
00785 
00786 
00787         myled= !myled;
00788         _count = t.read_ms();
00789 
00790         if(_count > 1<<21) {
00791             t.start(); // start the timer over again if ~30 minutes has passed
00792             _count = 0;
00793             deltat= 0;
00794             lastUpdate = t.read_us();
00795         }
00796         sum = 0;
00797         sumCount = 0;
00798     }
00799 }
00800 
00801 
00802 void MPU9250::imuSetup()
00803 {
00804     //Set up I2C
00805     i2c.frequency(400000);  // use fast (400 kHz) I2C
00806 
00807     pc.printf("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock);
00808 
00809     t.start();
00810 //  lcd.setBrightness(0.05);
00811 
00812 
00813     // Read the WHO_AM_I register, this is a good test of communication
00814     uint8_t whoami = mpu9250.readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250);  // Read WHO_AM_I register for MPU-9250
00815     pc.printf("I AM 0x%x\n\r", whoami);
00816     pc.printf("I SHOULD BE 0x71\n\r");
00817 
00818     if (whoami == 0x71) { // WHO_AM_I should always be 0x68
00819         pc.printf("MPU9250 WHO_AM_I is 0x%x\n\r", whoami);
00820         pc.printf("MPU9250 is online...\n\r");
00821         sprintf(buffer, "0x%x", whoami);
00822         wait(1);
00823 
00824         mpu9250.resetMPU9250(); // Reset registers to default in preparation for device calibration
00825         mpu9250.MPU9250SelfTest(SelfTest); // Start by performing self test and reporting values
00826         pc.printf("x-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[0]);
00827         pc.printf("y-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[1]);
00828         pc.printf("z-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[2]);
00829         pc.printf("x-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[3]);
00830         pc.printf("y-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[4]);
00831         pc.printf("z-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[5]);
00832         mpu9250.calibrateMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers
00833         pc.printf("x gyro bias = %f\n\r", gyroBias[0]);
00834         pc.printf("y gyro bias = %f\n\r", gyroBias[1]);
00835         pc.printf("z gyro bias = %f\n\r", gyroBias[2]);
00836         pc.printf("x accel bias = %f\n\r", accelBias[0]);
00837         pc.printf("y accel bias = %f\n\r", accelBias[1]);
00838         pc.printf("z accel bias = %f\n\r", accelBias[2]);
00839         wait(2);
00840         mpu9250.initMPU9250();
00841         pc.printf("MPU9250 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature
00842         mpu9250.initAK8963(magCalibration);
00843         pc.printf("AK8963 initialized for active data mode....\n\r"); // Initialize device for active mode read of magnetometer
00844         pc.printf("Accelerometer full-scale range = %f  g\n\r", 2.0f*(float)(1<<Ascale));
00845         pc.printf("Gyroscope full-scale range = %f  deg/s\n\r", 250.0f*(float)(1<<Gscale));
00846         if(Mscale == 0) pc.printf("Magnetometer resolution = 14  bits\n\r");
00847         if(Mscale == 1) pc.printf("Magnetometer resolution = 16  bits\n\r");
00848         if(Mmode == 2) pc.printf("Magnetometer ODR = 8 Hz\n\r");
00849         if(Mmode == 6) pc.printf("Magnetometer ODR = 100 Hz\n\r");
00850         wait(1);
00851     } else {
00852         pc.printf("Could not connect to MPU9250: \n\r");
00853         pc.printf("%#x \n",  whoami);
00854         sprintf(buffer, "WHO_AM_I 0x%x", whoami);
00855 
00856         while(1) {
00857             // Loop forever if communication doesn't happen
00858             pc.printf("no IMU detected (verify if it's plugged in)\n\r");
00859         }
00860     }
00861 
00862     mpu9250.getAres(); // Get accelerometer sensitivity
00863     mpu9250.getGres(); // Get gyro sensitivity
00864     mpu9250.getMres(); // Get magnetometer sensitivity
00865     pc.printf("Accelerometer sensitivity is %f LSB/g \n\r", 1.0f/aRes);
00866     pc.printf("Gyroscope sensitivity is %f LSB/deg/s \n\r", 1.0f/gRes);
00867     pc.printf("Magnetometer sensitivity is %f LSB/G \n\r", 1.0f/mRes);
00868     magbias[0] = +470.;  // User environmental x-axis correction in milliGauss, should be automatically calculated
00869     magbias[1] = +120.;  // User environmental x-axis correction in milliGauss
00870     magbias[2] = +125.;  // User environmental x-axis correction in milliGauss
00871 }
00872 
00873 accData_t MPU9250::getVelocityFromIMU(){
00874     readIMU();
00875     
00876     return myData;
00877 }