Quadrirotor

Dependencies:   CommonTypes ESC Matrix PID Servo kalman mbed-rtos mbed

Fork of Nucleo_MPU_9250 by Alan Huchin Herrera

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers MPU9250.cpp Source File

MPU9250.cpp

00001 #include "MPU9250.h"
00002 
00003 // Set initial input parameters
00004 enum Ascale {
00005   AFS_2G = 0,
00006   AFS_4G,
00007   AFS_8G,
00008   AFS_16G
00009 };
00010 
00011 enum Gscale {
00012   GFS_250DPS = 0,
00013   GFS_500DPS,
00014   GFS_1000DPS,
00015   GFS_2000DPS
00016 };
00017 
00018 enum Mscale {
00019   MFS_14BITS = 0, // 0.6 mG per LSB
00020   MFS_16BITS      // 0.15 mG per LSB
00021 };
00022 
00023 float ax,ay,az;
00024 float gx,gy,gz;
00025 float mx,my,mz;
00026 int16_t accelData[3],gyroData[3],tempData;
00027 float accelBias[3] = {0, 0, 0};  // Bias corrections for acc
00028 float gyroBias[3] = {0, 0, 0}; 
00029 extern float magCalibration[3]= {0, 0, 0};
00030 extern float magbias[3]= {0, 0, 0}, magScale[3]  = {0, 0, 0};
00031  float SelfTest[6];
00032 
00033 int delt_t = 0; // used to control display output rate
00034 int count = 0;  // used to control display output rate
00035 
00036 // parameters for 6 DoF sensor fusion calculations
00037 float PI = 3.14159265358979323846f;
00038 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
00039 float beta = sqrt(3.0f / 4.0f) * GyroMeasError;  // compute beta
00040 float GyroMeasDrift = PI * (1.0f / 180.0f);      // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s)
00041 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
00042 #define Kp 0.98 // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral
00043 #define Ki 0.0000001f
00044 
00045 float pitch, yaw, roll;
00046 float deltat = 0.0f;                             // integration interval for both filter schemes
00047 int lastUpdate = 0, firstUpdate = 0, Now = 0;    // used to calculate integration interval                               // used to calculate integration interval
00048 float q[4] = {1.0f, 0.0f, 0.0f, 0.0f};           // vector to hold quaternion
00049 float eInt[3] = {0.0f, 0.0f, 0.0f};      
00050 
00051 uint8_t Ascale = AFS_16G;     // AFS_2G, AFS_4G, AFS_8G, AFS_16G
00052 uint8_t Gscale = GFS_2000DPS; // GFS_250DPS, GFS_500DPS, GFS_1000DPS, GFS_2000DPS
00053 uint8_t Mscale = MFS_16BITS; // MFS_14BITS or MFS_16BITS, 14-bit or 16-bit magnetometer resolution
00054 uint8_t Mmode = 0x06;        // Either 8 Hz 0x02) or 100 Hz (0x06) magnetometer data ODR  
00055 float aRes, gRes, mRes; 
00056 
00057 MPU9250::MPU9250(PinName sda, PinName scl) : i2c(sda, scl) {
00058     //this->setSleepMode(false);
00059     i2c.frequency(400000);
00060     //Initializations:
00061     currentGyroRange = 0;
00062     currentAcceleroRange=0;
00063 }
00064 
00065 //--------------------------------------------------
00066 //--------------------CONFIG------------------------
00067 //--------------------------------------------------
00068 
00069 void MPU9250::getAres()
00070 {
00071     switch(Ascale)
00072     {
00073         case AFS_2G:
00074             aRes = 2.0/32768.0;
00075             break;
00076         case AFS_4G:
00077             aRes = 4.0/32768.0;
00078             break;
00079         case AFS_8G:
00080             aRes = 8.0/32768.0;
00081             break;
00082         case AFS_16G:
00083             aRes = 16.0/32768.0;
00084             break;         
00085     }
00086 }
00087 
00088 void MPU9250::getGres()
00089 {
00090     switch(Gscale)
00091     {
00092         case GFS_250DPS:
00093             gRes = 250.0/32768.0;
00094             break;
00095         case GFS_500DPS:
00096             gRes = 500.0/32768.0;
00097             break;
00098         case GFS_1000DPS:
00099             gRes = 1000.0/32768.0;
00100             break;
00101         case GFS_2000DPS:
00102             gRes = 2000.0/32768.0;
00103             break;
00104     }
00105 }
00106 
00107 void MPU9250::getMres() {
00108   switch (Mscale)
00109   {
00110     // Possible magnetometer scales (and their register bit settings) are:
00111     // 14 bit resolution (0) and 16 bit resolution (1)
00112     case MFS_14BITS:
00113           mRes = 10.0*4219.0/8190.0; // Proper scale to return milliGauss
00114           break;
00115     case MFS_16BITS:
00116           mRes = 10.0*4219.0/32760.0; // Proper scale to return milliGauss
00117           break;
00118   }
00119 }
00120 //--------------------------------------------------
00121 //-------------------General------------------------
00122 //--------------------------------------------------
00123 
00124 void MPU9250::writeByte(uint8_t address, uint8_t subAddress, uint8_t data)
00125 {
00126    char data_write[2];
00127    data_write[0] = subAddress;
00128    data_write[1] = data;
00129    i2c.write(address, data_write, 2, 0);
00130 }
00131 
00132 char MPU9250::readByte(uint8_t address, uint8_t subAddress)
00133 {
00134     char data[1]; // `data` will store the register data     
00135     char data_write[1];
00136     data_write[0] = subAddress;
00137     i2c.write(address, data_write, 1, 1); // no stop
00138     i2c.read(address, data, 1, 0); 
00139     return data[0]; 
00140 }
00141 
00142 void MPU9250::readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest)
00143 {     
00144     char data[14];
00145     char data_write[1];
00146     data_write[0] = subAddress;
00147     i2c.write(address, data_write, 1, 1); // no stop
00148     i2c.read(address, data, count, 0); 
00149     for(int ii = 0; ii < count; ii++) {
00150      dest[ii] = data[ii];
00151     }
00152 } 
00153 
00154 
00155 void MPU9250::readAccelData(int16_t * destination)
00156 {
00157   uint8_t rawData[6];  // x/y/z accel register data stored here
00158   readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]);  // Read the six raw data registers into data array
00159   destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ;  // Turn the MSB and LSB into a signed 16-bit value
00160   destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;  
00161   destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 
00162 }
00163 
00164 void MPU9250::readGyroData(int16_t * destination)
00165 {
00166   uint8_t rawData[6];  // x/y/z gyro register data stored here
00167   readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]);  // Read the six raw data registers sequentially into data array
00168   destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ;  // Turn the MSB and LSB into a signed 16-bit value
00169   destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;  
00170   destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 
00171 }
00172 
00173 void MPU9250::readMagData(int16_t * destination)
00174 {
00175   uint8_t rawData[7];  // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition
00176   if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // wait for magnetometer data ready bit to be set
00177   readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]);  // Read the six raw data and ST2 registers sequentially into data array
00178   uint8_t c = rawData[6]; // End data read by reading ST2 register
00179     if(!(c & 0x08)) { // Check if magnetic sensor overflow set, if not then report data
00180     destination[0] = (int16_t)(((int16_t)rawData[1] << 8) | rawData[0]);  // Turn the MSB and LSB into a signed 16-bit value
00181     destination[1] = (int16_t)(((int16_t)rawData[3] << 8) | rawData[2]) ;  // Data stored as little Endian
00182     destination[2] = (int16_t)(((int16_t)rawData[5] << 8) | rawData[4]) ; 
00183    }
00184   }
00185 }
00186 
00187 int16_t MPU9250::readTempData()
00188 {
00189   uint8_t rawData[2];  // x/y/z gyro register data stored here
00190   readBytes(MPU9250_ADDRESS, TEMP_OUT_H, 2, &rawData[0]);  // Read the two raw data registers sequentially into data array 
00191   return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ;  // Turn the MSB and LSB into a 16-bit value
00192 }
00193 
00194 void MPU9250::resetMPU9250() {
00195   // reset device
00196   writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
00197   wait(0.1);
00198   }
00199   
00200 void MPU9250::initAK8963(float * destination)
00201 {
00202   // First extract the factory calibration for each magnetometer axis
00203   uint8_t rawData[3];  // x/y/z gyro calibration data stored here
00204   writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer  
00205   wait(0.01);
00206   writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode
00207   wait(0.01);
00208   readBytes(AK8963_ADDRESS, AK8963_ASAX, 3, &rawData[0]);  // Read the x-, y-, and z-axis calibration values
00209   destination[0] =  (float)(rawData[0] - 128)/256.0f + 1.0f;   // Return x-axis sensitivity adjustment values, etc.
00210   destination[1] =  (float)(rawData[1] - 128)/256.0f + 1.0f;  
00211   destination[2] =  (float)(rawData[2] - 128)/256.0f + 1.0f; 
00212   writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer  
00213   wait(0.01);
00214   // Configure the magnetometer for continuous read and highest resolution
00215   // set Mscale bit 4 to 1 (0) to enable 16 (14) bit resolution in CNTL register,
00216   // and enable continuous mode data acquisition Mmode (bits [3:0]), 0010 for 8 Hz and 0110 for 100 Hz sample rates
00217   writeByte(AK8963_ADDRESS, AK8963_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR
00218   wait(0.01);
00219 }
00220 
00221 void MPU9250::initMPU9250()
00222 {  
00223  // Initialize MPU9250 device
00224  // wake up device
00225   writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors 
00226   wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt  
00227 
00228  // get stable time source
00229   writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01);  // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
00230 
00231  // Configure Gyro and Accelerometer
00232  // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively; 
00233  // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both
00234  // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate
00235   writeByte(MPU9250_ADDRESS, CONFIG, 0x03);  
00236  
00237  // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV)
00238   writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x04);  // Use a 200 Hz rate; the same rate set in CONFIG above
00239  
00240  // Set gyroscope full scale range
00241  // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3
00242   uint8_t c = readByte(MPU9250_ADDRESS, GYRO_CONFIG); // get current GYRO_CONFIG register value
00243  // c = c & ~0xE0; // Clear self-test bits [7:5] 
00244   c = c & ~0x02; // Clear Fchoice bits [1:0] 
00245   c = c & ~0x18; // Clear AFS bits [4:3]
00246   c = c | Gscale << 3; // Set full scale range for the gyro
00247  // c =| 0x00; // Set Fchoice for the gyro to 11 by writing its inverse to bits 1:0 of GYRO_CONFIG
00248   writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c ); // Write new GYRO_CONFIG value to register
00249   
00250  // Set accelerometer full-scale range configuration
00251   c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG); // get current ACCEL_CONFIG register value
00252  // c = c & ~0xE0; // Clear self-test bits [7:5] 
00253   c = c & ~0x18;  // Clear AFS bits [4:3]
00254   c = c | Ascale << 3; // Set full scale range for the accelerometer 
00255   writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c); // Write new ACCEL_CONFIG register value
00256 
00257  // Set accelerometer sample rate configuration
00258  // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for
00259  // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz
00260   c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2); // get current ACCEL_CONFIG2 register value
00261   c = c & ~0x0F; // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0])  
00262   c = c | 0x03;  // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz
00263   writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c); // Write new ACCEL_CONFIG2 register value
00264 
00265  // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates, 
00266  // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting
00267 
00268   // Configure Interrupts and Bypass Enable
00269   // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips 
00270   // can join the I2C bus and all can be controlled by the Arduino as master
00271 
00272 #if USE_ISR 
00273    writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x12);  // INT is 50 microsecond pulse and any read to clear  
00274 #else
00275    writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22);
00276 #endif 
00277    writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01);  // Enable data ready (bit 0) interrupt
00278 }
00279 
00280 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average
00281 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers.
00282 void MPU9250::calibrateMPU9250 (float * dest1, float * dest2)
00283 {  
00284   uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data
00285   uint16_t ii, packet_count, fifo_count;
00286   int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0};
00287   
00288 // reset device, reset all registers, clear gyro and accelerometer bias registers
00289   writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
00290   wait(0.1);  
00291    
00292 // get stable time source
00293 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
00294   writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01);  
00295   writeByte(MPU9250_ADDRESS, PWR_MGMT_2, 0x00); 
00296   wait(0.2);
00297   
00298 // Configure device for bias calculation
00299   writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x00);   // Disable all interrupts
00300   writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00);      // Disable FIFO
00301   writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00);   // Turn on internal clock source
00302   writeByte(MPU9250_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master
00303   writeByte(MPU9250_ADDRESS, USER_CTRL, 0x00);    // Disable FIFO and I2C master modes
00304   writeByte(MPU9250_ADDRESS, USER_CTRL, 0x0C);    // Reset FIFO and DMP
00305   wait(0.015);
00306   
00307 // Configure MPU9250 gyro and accelerometer for bias calculation
00308   writeByte(MPU9250_ADDRESS, CONFIG, 0x01);      // Set low-pass filter to 188 Hz
00309   writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00);  // Set sample rate to 1 kHz
00310   writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00);  // Set gyro full-scale to 250 degrees per second, maximum sensitivity
00311   writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity
00312  
00313   uint16_t  gyrosensitivity  = 131;   // = 131 LSB/degrees/sec
00314   uint16_t  accelsensitivity = 16384;  // = 16384 LSB/g
00315 
00316 // Configure FIFO to capture accelerometer and gyro data for bias calculation
00317   writeByte(MPU9250_ADDRESS, USER_CTRL, 0x40);   // Enable FIFO  
00318   writeByte(MPU9250_ADDRESS, FIFO_EN, 0x78);     // Enable gyro and accelerometer sensors for FIFO (max size 512 bytes in MPU-9250)
00319   wait(0.04); // accumulate 40 samples in 80 milliseconds = 480 bytes
00320 
00321 // At end of sample accumulation, turn off FIFO sensor read
00322   writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00);        // Disable gyro and accelerometer sensors for FIFO
00323   readBytes(MPU9250_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count
00324   fifo_count = ((uint16_t)data[0] << 8) | data[1];
00325   packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging
00326 
00327   for (ii = 0; ii < packet_count; ii++) {
00328     int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0};
00329     readBytes(MPU9250_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging
00330     accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1]  ) ;  // Form signed 16-bit integer for each sample in FIFO
00331     accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3]  ) ;
00332     accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5]  ) ;    
00333     gyro_temp[0]  = (int16_t) (((int16_t)data[6] << 8) | data[7]  ) ;
00334     gyro_temp[1]  = (int16_t) (((int16_t)data[8] << 8) | data[9]  ) ;
00335     gyro_temp[2]  = (int16_t) (((int16_t)data[10] << 8) | data[11]) ;
00336     
00337     accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases
00338     accel_bias[1] += (int32_t) accel_temp[1];
00339     accel_bias[2] += (int32_t) accel_temp[2];
00340     gyro_bias[0]  += (int32_t) gyro_temp[0];
00341     gyro_bias[1]  += (int32_t) gyro_temp[1];
00342     gyro_bias[2]  += (int32_t) gyro_temp[2];
00343             
00344 }
00345     accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases
00346     accel_bias[1] /= (int32_t) packet_count;
00347     accel_bias[2] /= (int32_t) packet_count;
00348     gyro_bias[0]  /= (int32_t) packet_count;
00349     gyro_bias[1]  /= (int32_t) packet_count;
00350     gyro_bias[2]  /= (int32_t) packet_count;
00351     
00352   if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;}  // Remove gravity from the z-axis accelerometer bias calculation
00353   else {accel_bias[2] += (int32_t) accelsensitivity;}
00354  
00355 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup
00356   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
00357   data[1] = (-gyro_bias[0]/4)       & 0xFF; // Biases are additive, so change sign on calculated average gyro biases
00358   data[2] = (-gyro_bias[1]/4  >> 8) & 0xFF;
00359   data[3] = (-gyro_bias[1]/4)       & 0xFF;
00360   data[4] = (-gyro_bias[2]/4  >> 8) & 0xFF;
00361   data[5] = (-gyro_bias[2]/4)       & 0xFF;
00362 
00363 /// Push gyro biases to hardware registers
00364 /*  writeByte(MPU9250_ADDRESS, XG_OFFSET_H, data[0]);
00365   writeByte(MPU9250_ADDRESS, XG_OFFSET_L, data[1]);
00366   writeByte(MPU9250_ADDRESS, YG_OFFSET_H, data[2]);
00367   writeByte(MPU9250_ADDRESS, YG_OFFSET_L, data[3]);
00368   writeByte(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]);
00369   writeByte(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]);
00370 */
00371   dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction
00372   dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity;
00373   dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity;
00374 
00375 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain
00376 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold
00377 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature
00378 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that
00379 // the accelerometer biases calculated above must be divided by 8.
00380 
00381   int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases
00382   readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values
00383   accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1];
00384   readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]);
00385   accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1];
00386   readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]);
00387   accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1];
00388   
00389   uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers
00390   uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis
00391   
00392   for(ii = 0; ii < 3; ii++) {
00393     if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit
00394   }
00395 
00396   // Construct total accelerometer bias, including calculated average accelerometer bias from above
00397   accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale)
00398   accel_bias_reg[1] -= (accel_bias[1]/8);
00399   accel_bias_reg[2] -= (accel_bias[2]/8);
00400  
00401   data[0] = (accel_bias_reg[0] >> 8) & 0xFF;
00402   data[1] = (accel_bias_reg[0])      & 0xFF;
00403   data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers
00404   data[2] = (accel_bias_reg[1] >> 8) & 0xFF;
00405   data[3] = (accel_bias_reg[1])      & 0xFF;
00406   data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers
00407   data[4] = (accel_bias_reg[2] >> 8) & 0xFF;
00408   data[5] = (accel_bias_reg[2])      & 0xFF;
00409   data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers
00410 
00411 // Apparently this is not working for the acceleration biases in the MPU-9250
00412 // Are we handling the temperature correction bit properly?
00413 // Push accelerometer biases to hardware registers
00414 /*  writeByte(MPU9250_ADDRESS, XA_OFFSET_H, data[0]);
00415   writeByte(MPU9250_ADDRESS, XA_OFFSET_L, data[1]);
00416   writeByte(MPU9250_ADDRESS, YA_OFFSET_H, data[2]);
00417   writeByte(MPU9250_ADDRESS, YA_OFFSET_L, data[3]);
00418   writeByte(MPU9250_ADDRESS, ZA_OFFSET_H, data[4]);
00419   writeByte(MPU9250_ADDRESS, ZA_OFFSET_L, data[5]);
00420 */
00421 // Output scaled accelerometer biases for manual subtraction in the main program
00422    dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; 
00423    dest2[1] = (float)accel_bias[1]/(float)accelsensitivity;
00424    dest2[2] = (float)accel_bias[2]/(float)accelsensitivity;
00425 }
00426 
00427 void MPU9250::magcalMPU9250(float * dest1, float * dest2) 
00428 {
00429   uint16_t ii = 0, sample_count = 0;
00430   int32_t mag_bias[3] = {0, 0, 0}, mag_scale[3] = {0, 0, 0};
00431   int16_t mag_max[3] = {-32767, -32767, -32767}, mag_min[3] = {32767, 32767, 32767}, mag_temp[3] = {0, 0, 0};
00432   
00433     // shoot for ~fifteen seconds of mag data
00434     if(Mmode == 0x02) sample_count = 128;  // at 8 Hz ODR, new mag data is available every 125 ms
00435     if(Mmode == 0x06) sample_count = 1500;  // at 100 Hz ODR, new mag data is available every 10 ms
00436     
00437    for(ii = 0; ii < sample_count; ii++) {
00438     readMagData(mag_temp);  // Read the mag data  
00439     
00440     for (int jj = 0; jj < 3; jj++) {
00441       if(mag_temp[jj] > mag_max[jj]) mag_max[jj] = mag_temp[jj];
00442       if(mag_temp[jj] < mag_min[jj]) mag_min[jj] = mag_temp[jj];
00443     }
00444     
00445     if(Mmode == 0x02) wait(0.135);  // at 8 Hz ODR, new mag data is available every 125 ms
00446     if(Mmode == 0x06) wait(0.012);  // at 100 Hz ODR, new mag data is available every 10 ms
00447     }
00448 
00449    // Get hard iron correction
00450     mag_bias[0]  = (mag_max[0] + mag_min[0])/2;  // get average x mag bias in counts
00451     mag_bias[1]  = (mag_max[1] + mag_min[1])/2;  // get average y mag bias in counts
00452     mag_bias[2]  = (mag_max[2] + mag_min[2])/2;  // get average z mag bias in counts
00453     
00454     dest1[0] = (float) mag_bias[0]*mRes*magCalibration[0];  // save mag biases in G for main program
00455     dest1[1] = (float) mag_bias[1]*mRes*magCalibration[1];   
00456     dest1[2] = (float) mag_bias[2]*mRes*magCalibration[2];  
00457        
00458     // Get soft iron correction estimate
00459     mag_scale[0]  = (mag_max[0] - mag_min[0])/2;  // get average x axis max chord length in counts
00460     mag_scale[1]  = (mag_max[1] - mag_min[1])/2;  // get average y axis max chord length in counts
00461     mag_scale[2]  = (mag_max[2] - mag_min[2])/2;  // get average z axis max chord length in counts
00462 
00463     float avg_rad = mag_scale[0] + mag_scale[1] + mag_scale[2];
00464     avg_rad /= 3.0;
00465 
00466     dest2[0] = avg_rad/((float)mag_scale[0]);
00467     dest2[1] = avg_rad/((float)mag_scale[1]);
00468     dest2[2] = avg_rad/((float)mag_scale[2]);
00469 }
00470 
00471 
00472 // Accelerometer and gyroscope self test; check calibration wrt factory settings
00473 void MPU9250::MPU9250SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass
00474 {
00475    uint8_t rawData[6] = {0, 0, 0, 0, 0, 0};
00476    uint8_t selfTest[6];
00477     int32_t gAvg[3] = {0}, aAvg[3] = {0}, aSTAvg[3] = {0}, gSTAvg[3] = {0};
00478    float factoryTrim[6];
00479    uint8_t FS = 0;
00480    
00481   writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz
00482   writeByte(MPU9250_ADDRESS, CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz
00483   writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 1<<FS); // Set full scale range for the gyro to 250 dps
00484   writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz
00485   writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 1<<FS); // Set full scale range for the accelerometer to 2 g
00486 
00487   for( int ii = 0; ii < 200; ii++) { // get average current values of gyro and acclerometer
00488   
00489   readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
00490   aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
00491   aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
00492   aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
00493   
00494     readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
00495   gAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
00496   gAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
00497   gAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
00498   }
00499   
00500   for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average current readings
00501   aAvg[ii] /= 200;
00502   gAvg[ii] /= 200;
00503   }
00504   
00505 // Configure the accelerometer for self-test
00506    writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g
00507    writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s
00508    wait(0.025); // Delay a while to let the device stabilize
00509 
00510   for( int ii = 0; ii < 200; ii++) { // get average self-test values of gyro and acclerometer
00511   
00512   readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
00513   aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
00514   aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
00515   aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
00516   
00517     readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
00518   gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
00519   gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
00520   gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
00521   }
00522   
00523   for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average self-test readings
00524   aSTAvg[ii] /= 200;
00525   gSTAvg[ii] /= 200;
00526   }
00527   
00528  // Configure the gyro and accelerometer for normal operation
00529    writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00);
00530    writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00);
00531    wait(0.025); // Delay a while to let the device stabilize
00532    
00533    // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg
00534    selfTest[0] = readByte(MPU9250_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results
00535    selfTest[1] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_ACCEL); // Y-axis accel self-test results
00536    selfTest[2] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_ACCEL); // Z-axis accel self-test results
00537    selfTest[3] = readByte(MPU9250_ADDRESS, SELF_TEST_X_GYRO); // X-axis gyro self-test results
00538    selfTest[4] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_GYRO); // Y-axis gyro self-test results
00539    selfTest[5] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_GYRO); // Z-axis gyro self-test results
00540 
00541   // Retrieve factory self-test value from self-test code reads
00542    factoryTrim[0] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[0] - 1.0) )); // FT[Xa] factory trim calculation
00543    factoryTrim[1] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[1] - 1.0) )); // FT[Ya] factory trim calculation
00544    factoryTrim[2] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[2] - 1.0) )); // FT[Za] factory trim calculation
00545    factoryTrim[3] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[3] - 1.0) )); // FT[Xg] factory trim calculation
00546    factoryTrim[4] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[4] - 1.0) )); // FT[Yg] factory trim calculation
00547    factoryTrim[5] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[5] - 1.0) )); // FT[Zg] factory trim calculation
00548  
00549  // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response
00550  // To get percent, must multiply by 100
00551    for (int i = 0; i < 3; i++) {
00552      destination[i] = 100.0*((float)(aSTAvg[i] - aAvg[i]))/factoryTrim[i] - 100.; // Report percent differences
00553      destination[i+3] = 100.0*((float)(gSTAvg[i] - gAvg[i]))/factoryTrim[i+3] - 100.; // Report percent differences
00554    }
00555    
00556 }
00557 
00558 void MPU9250::MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
00559 {
00560             float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3];   // short name local variable for readability
00561             float norm;
00562             float hx, hy, _2bx, _2bz;
00563             float s1, s2, s3, s4;
00564             float qDot1, qDot2, qDot3, qDot4;
00565 
00566             // Auxiliary variables to avoid repeated arithmetic
00567             float _2q1mx;
00568             float _2q1my;
00569             float _2q1mz;
00570             float _2q2mx;
00571             float _4bx;
00572             float _4bz;
00573             float _2q1 = 2.0f * q1;
00574             float _2q2 = 2.0f * q2;
00575             float _2q3 = 2.0f * q3;
00576             float _2q4 = 2.0f * q4;
00577             float _2q1q3 = 2.0f * q1 * q3;
00578             float _2q3q4 = 2.0f * q3 * q4;
00579             float q1q1 = q1 * q1;
00580             float q1q2 = q1 * q2;
00581             float q1q3 = q1 * q3;
00582             float q1q4 = q1 * q4;
00583             float q2q2 = q2 * q2;
00584             float q2q3 = q2 * q3;
00585             float q2q4 = q2 * q4;
00586             float q3q3 = q3 * q3;
00587             float q3q4 = q3 * q4;
00588             float q4q4 = q4 * q4;
00589 
00590             // Normalise accelerometer measurement
00591             norm = sqrt(ax * ax + ay * ay + az * az);
00592             if (norm == 0.0f) return; // handle NaN
00593             norm = 1.0f/norm;
00594             ax *= norm;
00595             ay *= norm;
00596             az *= norm;
00597 
00598             // Normalise magnetometer measurement
00599             norm = sqrt(mx * mx + my * my + mz * mz);
00600             if (norm == 0.0f) return; // handle NaN
00601             norm = 1.0f/norm;
00602             mx *= norm;
00603             my *= norm;
00604             mz *= norm;
00605 
00606             // Reference direction of Earth's magnetic field
00607             _2q1mx = 2.0f * q1 * mx;
00608             _2q1my = 2.0f * q1 * my;
00609             _2q1mz = 2.0f * q1 * mz;
00610             _2q2mx = 2.0f * q2 * mx;
00611             hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4;
00612             hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4;
00613             _2bx = sqrt(hx * hx + hy * hy);
00614             _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4;
00615             _4bx = 2.0f * _2bx;
00616             _4bz = 2.0f * _2bz;
00617 
00618             // Gradient decent algorithm corrective step
00619             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);
00620             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);
00621             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);
00622             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);
00623             norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4);    // normalise step magnitude
00624             norm = 1.0f/norm;
00625             s1 *= norm;
00626             s2 *= norm;
00627             s3 *= norm;
00628             s4 *= norm;
00629 
00630             // Compute rate of change of quaternion
00631             qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1;
00632             qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2;
00633             qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3;
00634             qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4;
00635 
00636             // Integrate to yield quaternion
00637             q1 += qDot1 * deltat;
00638             q2 += qDot2 * deltat;
00639             q3 += qDot3 * deltat;
00640             q4 += qDot4 * deltat;
00641             norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);    // normalise quaternion
00642             norm = 1.0f/norm;
00643             q[0] = q1 * norm;
00644             q[1] = q2 * norm;
00645             q[2] = q3 * norm;
00646             q[3] = q4 * norm;
00647 
00648 }
00649     
00650  // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and
00651  // measured ones. 
00652 void MPU9250::MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
00653 {
00654             float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3];   // short name local variable for readability
00655             float norm;
00656             float hx, hy, bx, bz;
00657             float vx, vy, vz, wx, wy, wz;
00658             float ex, ey, ez;
00659             float pa, pb, pc;
00660 
00661             // Auxiliary variables to avoid repeated arithmetic
00662             float q1q1 = q1 * q1;
00663             float q1q2 = q1 * q2;
00664             float q1q3 = q1 * q3;
00665             float q1q4 = q1 * q4;
00666             float q2q2 = q2 * q2;
00667             float q2q3 = q2 * q3;
00668             float q2q4 = q2 * q4;
00669             float q3q3 = q3 * q3;
00670             float q3q4 = q3 * q4;
00671             float q4q4 = q4 * q4;   
00672 
00673             // Normalise accelerometer measurement
00674             norm = sqrt(ax * ax + ay * ay + az * az);
00675             if (norm == 0.0f) return; // handle NaN
00676             norm = 1.0f / norm;        // use reciprocal for division
00677             ax *= norm;
00678             ay *= norm;
00679             az *= norm;
00680 
00681             // Normalise magnetometer measurement
00682             norm = sqrt(mx * mx + my * my + mz * mz);
00683             if (norm == 0.0f) return; // handle NaN
00684             norm = 1.0f / norm;        // use reciprocal for division
00685             mx *= norm;
00686             my *= norm;
00687             mz *= norm;
00688 
00689             // Reference direction of Earth's magnetic field
00690             hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3);
00691             hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2);
00692             bx = sqrt((hx * hx) + (hy * hy));
00693             bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3);
00694 
00695             // Estimated direction of gravity and magnetic field
00696             vx = 2.0f * (q2q4 - q1q3);
00697             vy = 2.0f * (q1q2 + q3q4);
00698             vz = q1q1 - q2q2 - q3q3 + q4q4;
00699             wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3);
00700             wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4);
00701             wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3);  
00702 
00703             // Error is cross product between estimated direction and measured direction of gravity
00704             ex = (ay * vz - az * vy) + (my * wz - mz * wy);
00705             ey = (az * vx - ax * vz) + (mz * wx - mx * wz);
00706             ez = (ax * vy - ay * vx) + (mx * wy - my * wx);
00707             if (Ki > 0.0f)
00708             {
00709                 eInt[0] += ex;      // accumulate integral error
00710                 eInt[1] += ey;
00711                 eInt[2] += ez;
00712             }
00713             else
00714             {
00715                 eInt[0] = 0.0f;     // prevent integral wind up
00716                 eInt[1] = 0.0f;
00717                 eInt[2] = 0.0f;
00718             }
00719 
00720             // Apply feedback terms
00721             gx = gx + Kp * ex + Ki * eInt[0];
00722             gy = gy + Kp * ey + Ki * eInt[1];
00723             gz = gz + Kp * ez + Ki * eInt[2];
00724 
00725             // Integrate rate of change of quaternion
00726             pa = q2;
00727             pb = q3;
00728             pc = q4;
00729             q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat);
00730             q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat);
00731             q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat);
00732             q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat);
00733 
00734             // Normalise quaternion
00735             norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);
00736             norm = 1.0f / norm;
00737             q[0] = q1 * norm;
00738             q[1] = q2 * norm;
00739             q[2] = q3 * norm;
00740             q[3] = q4 * norm;
00741  
00742 }
00743