Bradley Kohler / MPU6050
Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers MPU6050.cpp Source File

MPU6050.cpp

00001 #include "mpu6050.h"
00002 
00003 int Gscale = GFS_250DPS;
00004 int Ascale = AFS_2G;
00005 
00006 I2C i2c(I2C_SDA, I2C_SCL);
00007 
00008 float aRes, gRes;
00009 
00010 int intPin = 12;
00011 
00012 int16_t accelCount[3];  // Stores the 16-bit signed accelerometer sensor output
00013 float ax, ay, az;       // Stores the real accel value in g's
00014 int16_t gyroCount[3];   // Stores the 16-bit signed gyro sensor output
00015 float gx, gy, gz;       // Stores the real gyro value in degrees per seconds
00016 float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer
00017 int16_t tempCount;   // Stores the real internal chip temperature in degrees Celsius
00018 float temperature;
00019 float SelfTest[6];
00020 
00021 int delt_t = 0; // used to control display output rate
00022 int count = 0;  // used to control display output rate
00023 
00024 // parameters for 6 DoF sensor fusion calculations
00025 //float PI = 3.14159265358979323846f;
00026 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
00027 float beta = sqrt(3.0f / 4.0f) * GyroMeasError;  // compute beta
00028 float GyroMeasDrift = PI * (1.0f / 180.0f);      // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s)
00029 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
00030 float pitch, yaw, roll;
00031 float deltat = 0.0f;                              // integration interval for both filter schemes
00032 int lastUpdate = 0, firstUpdate = 0, Now = 0;     // used to calculate integration interval                               // used to calculate integration interval
00033 float q[4] = {1.0f, 0.0f, 0.0f, 0.0f};            // vector to hold quaternion
00034 
00035 void mpu6050::writeByte(uint8_t address, uint8_t subAddress, uint8_t data){
00036     char data_write[2];
00037     data_write[0] = subAddress;
00038     data_write[1] = data;
00039     i2c.write(address, data_write, 2, 0);
00040 }
00041 
00042 char mpu6050::readByte(uint8_t address, uint8_t subAddress){
00043     char data[1]; // `data` will store the register data     
00044     char data_write[1];
00045     data_write[0] = subAddress;
00046     i2c.write(address, data_write, 1, 1); // no stop
00047     i2c.read(address, data, 1, 0); 
00048     return data[0]; 
00049 }
00050 
00051 void mpu6050::readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest){
00052     char data[14];
00053     char data_write[1];
00054     data_write[0] = subAddress;
00055     i2c.write(address, data_write, 1, 1); // no stop
00056     i2c.read(address, data, count, 0); 
00057     for(int ii = 0; ii < count; ii++) {
00058      dest[ii] = data[ii];
00059     }
00060 }
00061 
00062 void mpu6050::getGres() {
00063   switch (Gscale)
00064   {
00065     // Possible gyro scales (and their register bit settings) are:
00066     // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS  (11). 
00067         // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
00068     case GFS_250DPS:
00069           gRes = 250.0/32768.0;
00070           break;
00071     case GFS_500DPS:
00072           gRes = 500.0/32768.0;
00073           break;
00074     case GFS_1000DPS:
00075           gRes = 1000.0/32768.0;
00076           break;
00077     case GFS_2000DPS:
00078           gRes = 2000.0/32768.0;
00079           break;
00080   }
00081 }
00082 
00083 void mpu6050::getAres() {
00084   switch (Ascale)
00085   {
00086     // Possible accelerometer scales (and their register bit settings) are:
00087     // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs  (11). 
00088         // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
00089     case AFS_2G:
00090           aRes = 2.0/32768.0;
00091           break;
00092     case AFS_4G:
00093           aRes = 4.0/32768.0;
00094           break;
00095     case AFS_8G:
00096           aRes = 8.0/32768.0;
00097           break;
00098     case AFS_16G:
00099           aRes = 16.0/32768.0;
00100           break;
00101   }
00102 }
00103 
00104 void mpu6050::readAccelData(int16_t * destination)
00105 {
00106   uint8_t rawData[6];  // x/y/z accel register data stored here
00107   readBytes(MPU6050_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]);  // Read the six raw data registers into data array
00108   destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ;  // Turn the MSB and LSB into a signed 16-bit value
00109   destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;  
00110   destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 
00111 }
00112 
00113 void mpu6050::readGyroData(int16_t * destination)
00114 {
00115   uint8_t rawData[6];  // x/y/z gyro register data stored here
00116   readBytes(MPU6050_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]);  // Read the six raw data registers sequentially into data array
00117   destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ;  // Turn the MSB and LSB into a signed 16-bit value
00118   destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;  
00119   destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 
00120 }
00121 
00122 int16_t mpu6050::readTempData()
00123 {
00124   uint8_t rawData[2];  // x/y/z gyro register data stored here
00125   readBytes(MPU6050_ADDRESS, TEMP_OUT_H, 2, &rawData[0]);  // Read the two raw data registers sequentially into data array 
00126   return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ;  // Turn the MSB and LSB into a 16-bit value
00127 }
00128 
00129 // Configure the motion detection control for low power accelerometer mode
00130 void mpu6050::lowPowerAccelOnly()
00131 {
00132 
00133 // The sensor has a high-pass filter necessary to invoke to allow the sensor motion detection algorithms work properly
00134 // Motion detection occurs on free-fall (acceleration below a threshold for some time for all axes), motion (acceleration
00135 // above a threshold for some time on at least one axis), and zero-motion toggle (acceleration on each axis less than a 
00136 // threshold for some time sets this flag, motion above the threshold turns it off). The high-pass filter takes gravity out
00137 // consideration for these threshold evaluations; otherwise, the flags would be set all the time!
00138   
00139   uint8_t c = readByte(MPU6050_ADDRESS, PWR_MGMT_1);
00140   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c & ~0x30); // Clear sleep and cycle bits [5:6]
00141   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c |  0x30); // Set sleep and cycle bits [5:6] to zero to make sure accelerometer is running
00142 
00143   c = readByte(MPU6050_ADDRESS, PWR_MGMT_2);
00144   writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c & ~0x38); // Clear standby XA, YA, and ZA bits [3:5]
00145   writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c |  0x00); // Set XA, YA, and ZA bits [3:5] to zero to make sure accelerometer is running
00146     
00147   c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG);
00148   writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x07); // Clear high-pass filter bits [2:0]
00149 // Set high-pass filter to 0) reset (disable), 1) 5 Hz, 2) 2.5 Hz, 3) 1.25 Hz, 4) 0.63 Hz, or 7) Hold
00150   writeByte(MPU6050_ADDRESS, ACCEL_CONFIG,  c | 0x00);  // Set ACCEL_HPF to 0; reset mode disbaling high-pass filter
00151 
00152   c = readByte(MPU6050_ADDRESS, CONFIG);
00153   writeByte(MPU6050_ADDRESS, CONFIG, c & ~0x07); // Clear low-pass filter bits [2:0]
00154   writeByte(MPU6050_ADDRESS, CONFIG, c |  0x00);  // Set DLPD_CFG to 0; 260 Hz bandwidth, 1 kHz rate
00155     
00156   c = readByte(MPU6050_ADDRESS, INT_ENABLE);
00157   writeByte(MPU6050_ADDRESS, INT_ENABLE, c & ~0xFF);  // Clear all interrupts
00158   writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x40);  // Enable motion threshold (bits 5) interrupt only
00159   
00160 // Motion detection interrupt requires the absolute value of any axis to lie above the detection threshold
00161 // for at least the counter duration
00162   writeByte(MPU6050_ADDRESS, MOT_THR, 0x80); // Set motion detection to 0.256 g; LSB = 2 mg
00163   writeByte(MPU6050_ADDRESS, MOT_DUR, 0x01); // Set motion detect duration to 1  ms; LSB is 1 ms @ 1 kHz rate
00164   
00165   wait(0.1);  // Add delay for accumulation of samples
00166   
00167   c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG);
00168   writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x07); // Clear high-pass filter bits [2:0]
00169   writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c |  0x07);  // Set ACCEL_HPF to 7; hold the initial accleration value as a referance
00170    
00171   c = readByte(MPU6050_ADDRESS, PWR_MGMT_2);
00172   writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c & ~0xC7); // Clear standby XA, YA, and ZA bits [3:5] and LP_WAKE_CTRL bits [6:7]
00173   writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c |  0x47); // Set wakeup frequency to 5 Hz, and disable XG, YG, and ZG gyros (bits [0:2])  
00174 
00175   c = readByte(MPU6050_ADDRESS, PWR_MGMT_1);
00176   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c & ~0x20); // Clear sleep and cycle bit 5
00177   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c |  0x20); // Set cycle bit 5 to begin low power accelerometer motion interrupts
00178 
00179 }
00180 
00181 
00182 void mpu6050::reset() {
00183   // reset device
00184   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
00185   wait(0.1);
00186   }
00187   
00188   
00189 void mpu6050::init()
00190 {  
00191  // Initialize MPU6050 device
00192  // wake up device
00193   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors 
00194   wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt  
00195 
00196  // get stable time source
00197   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01);  // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
00198 
00199  // Configure Gyro and Accelerometer
00200  // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively; 
00201  // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both
00202  // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate
00203   writeByte(MPU6050_ADDRESS, CONFIG, 0x03);  
00204  
00205  // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV)
00206   writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x04);  // Use a 200 Hz rate; the same rate set in CONFIG above
00207  
00208  // Set gyroscope full scale range
00209  // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3
00210   uint8_t c =  readByte(MPU6050_ADDRESS, GYRO_CONFIG);
00211   writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 
00212   writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3]
00213   writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro
00214    
00215  // Set accelerometer configuration
00216   c =  readByte(MPU6050_ADDRESS, ACCEL_CONFIG);
00217   writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 
00218   writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3]
00219   writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer 
00220 
00221   // Configure Interrupts and Bypass Enable
00222   // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips 
00223   // can join the I2C bus and all can be controlled by the Arduino as master
00224    writeByte(MPU6050_ADDRESS, INT_PIN_CFG, 0x22);    
00225    writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x01);  // Enable data ready (bit 0) interrupt
00226 }
00227 
00228 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average
00229 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers.
00230 void mpu6050::calibrate(float * dest1, float * dest2)
00231 {  
00232   uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data
00233   uint16_t ii, packet_count, fifo_count;
00234   int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0};
00235   
00236 // reset device, reset all registers, clear gyro and accelerometer bias registers
00237   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
00238   wait(0.1);  
00239    
00240 // get stable time source
00241 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
00242   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01);  
00243   writeByte(MPU6050_ADDRESS, PWR_MGMT_2, 0x00); 
00244   wait(0.2);
00245   
00246 // Configure device for bias calculation
00247   writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x00);   // Disable all interrupts
00248   writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00);      // Disable FIFO
00249   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00);   // Turn on internal clock source
00250   writeByte(MPU6050_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master
00251   writeByte(MPU6050_ADDRESS, USER_CTRL, 0x00);    // Disable FIFO and I2C master modes
00252   writeByte(MPU6050_ADDRESS, USER_CTRL, 0x0C);    // Reset FIFO and DMP
00253   wait(0.015);
00254   
00255 // Configure MPU6050 gyro and accelerometer for bias calculation
00256   writeByte(MPU6050_ADDRESS, CONFIG, 0x01);      // Set low-pass filter to 188 Hz
00257   writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x00);  // Set sample rate to 1 kHz
00258   writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0x00);  // Set gyro full-scale to 250 degrees per second, maximum sensitivity
00259   writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity
00260  
00261   uint16_t  gyrosensitivity  = 131;   // = 131 LSB/degrees/sec
00262   uint16_t  accelsensitivity = 16384;  // = 16384 LSB/g
00263 
00264 // Configure FIFO to capture accelerometer and gyro data for bias calculation
00265   writeByte(MPU6050_ADDRESS, USER_CTRL, 0x40);   // Enable FIFO  
00266   writeByte(MPU6050_ADDRESS, FIFO_EN, 0x78);     // Enable gyro and accelerometer sensors for FIFO  (max size 1024 bytes in MPU-6050)
00267   wait(0.08); // accumulate 80 samples in 80 milliseconds = 960 bytes
00268 
00269 // At end of sample accumulation, turn off FIFO sensor read
00270   writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00);        // Disable gyro and accelerometer sensors for FIFO
00271   readBytes(MPU6050_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count
00272   fifo_count = ((uint16_t)data[0] << 8) | data[1];
00273   packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging
00274 
00275   for (ii = 0; ii < packet_count; ii++) {
00276     int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0};
00277     readBytes(MPU6050_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging
00278     accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1]  ) ;  // Form signed 16-bit integer for each sample in FIFO
00279     accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3]  ) ;
00280     accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5]  ) ;    
00281     gyro_temp[0]  = (int16_t) (((int16_t)data[6] << 8) | data[7]  ) ;
00282     gyro_temp[1]  = (int16_t) (((int16_t)data[8] << 8) | data[9]  ) ;
00283     gyro_temp[2]  = (int16_t) (((int16_t)data[10] << 8) | data[11]) ;
00284     
00285     accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases
00286     accel_bias[1] += (int32_t) accel_temp[1];
00287     accel_bias[2] += (int32_t) accel_temp[2];
00288     gyro_bias[0]  += (int32_t) gyro_temp[0];
00289     gyro_bias[1]  += (int32_t) gyro_temp[1];
00290     gyro_bias[2]  += (int32_t) gyro_temp[2];
00291             
00292 }
00293     accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases
00294     accel_bias[1] /= (int32_t) packet_count;
00295     accel_bias[2] /= (int32_t) packet_count;
00296     gyro_bias[0]  /= (int32_t) packet_count;
00297     gyro_bias[1]  /= (int32_t) packet_count;
00298     gyro_bias[2]  /= (int32_t) packet_count;
00299     
00300   if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;}  // Remove gravity from the z-axis accelerometer bias calculation
00301   else {accel_bias[2] += (int32_t) accelsensitivity;}
00302  
00303 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup
00304   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
00305   data[1] = (-gyro_bias[0]/4)       & 0xFF; // Biases are additive, so change sign on calculated average gyro biases
00306   data[2] = (-gyro_bias[1]/4  >> 8) & 0xFF;
00307   data[3] = (-gyro_bias[1]/4)       & 0xFF;
00308   data[4] = (-gyro_bias[2]/4  >> 8) & 0xFF;
00309   data[5] = (-gyro_bias[2]/4)       & 0xFF;
00310 
00311 // Push gyro biases to hardware registers
00312   writeByte(MPU6050_ADDRESS, XG_OFFS_USRH, data[0]); 
00313   writeByte(MPU6050_ADDRESS, XG_OFFS_USRL, data[1]);
00314   writeByte(MPU6050_ADDRESS, YG_OFFS_USRH, data[2]);
00315   writeByte(MPU6050_ADDRESS, YG_OFFS_USRL, data[3]);
00316   writeByte(MPU6050_ADDRESS, ZG_OFFS_USRH, data[4]);
00317   writeByte(MPU6050_ADDRESS, ZG_OFFS_USRL, data[5]);
00318 
00319   dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction
00320   dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity;
00321   dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity;
00322 
00323 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain
00324 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold
00325 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature
00326 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that
00327 // the accelerometer biases calculated above must be divided by 8.
00328 
00329   int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases
00330   readBytes(MPU6050_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values
00331   accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1];
00332   readBytes(MPU6050_ADDRESS, YA_OFFSET_H, 2, &data[0]);
00333   accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1];
00334   readBytes(MPU6050_ADDRESS, ZA_OFFSET_H, 2, &data[0]);
00335   accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1];
00336   
00337   uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers
00338   uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis
00339   
00340   for(ii = 0; ii < 3; ii++) {
00341     if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit
00342   }
00343 
00344   // Construct total accelerometer bias, including calculated average accelerometer bias from above
00345   accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale)
00346   accel_bias_reg[1] -= (accel_bias[1]/8);
00347   accel_bias_reg[2] -= (accel_bias[2]/8);
00348  
00349   data[0] = (accel_bias_reg[0] >> 8) & 0xFF;
00350   data[1] = (accel_bias_reg[0])      & 0xFF;
00351   data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers
00352   data[2] = (accel_bias_reg[1] >> 8) & 0xFF;
00353   data[3] = (accel_bias_reg[1])      & 0xFF;
00354   data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers
00355   data[4] = (accel_bias_reg[2] >> 8) & 0xFF;
00356   data[5] = (accel_bias_reg[2])      & 0xFF;
00357   data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers
00358 
00359   // Push accelerometer biases to hardware registers
00360 //  writeByte(MPU6050_ADDRESS, XA_OFFSET_H, data[0]);  
00361 //  writeByte(MPU6050_ADDRESS, XA_OFFSET_L_TC, data[1]);
00362 //  writeByte(MPU6050_ADDRESS, YA_OFFSET_H, data[2]);
00363 //  writeByte(MPU6050_ADDRESS, YA_OFFSET_L_TC, data[3]);  
00364 //  writeByte(MPU6050_ADDRESS, ZA_OFFSET_H, data[4]);
00365 //  writeByte(MPU6050_ADDRESS, ZA_OFFSET_L_TC, data[5]);
00366 
00367 // Output scaled accelerometer biases for manual subtraction in the main program
00368    dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; 
00369    dest2[1] = (float)accel_bias[1]/(float)accelsensitivity;
00370    dest2[2] = (float)accel_bias[2]/(float)accelsensitivity;
00371 }
00372 
00373 
00374 // Accelerometer and gyroscope self test; check calibration wrt factory settings
00375 void mpu6050::selfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass
00376 {
00377    uint8_t rawData[4] = {0, 0, 0, 0};
00378    uint8_t selfTest[6];
00379    float factoryTrim[6];
00380    
00381    // Configure the accelerometer for self-test
00382    writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0xF0); // Enable self test on all three axes and set accelerometer range to +/- 8 g
00383    writeByte(MPU6050_ADDRESS, GYRO_CONFIG,  0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s
00384    wait(0.25);  // Delay a while to let the device execute the self-test
00385    rawData[0] = readByte(MPU6050_ADDRESS, SELF_TEST_X); // X-axis self-test results
00386    rawData[1] = readByte(MPU6050_ADDRESS, SELF_TEST_Y); // Y-axis self-test results
00387    rawData[2] = readByte(MPU6050_ADDRESS, SELF_TEST_Z); // Z-axis self-test results
00388    rawData[3] = readByte(MPU6050_ADDRESS, SELF_TEST_A); // Mixed-axis self-test results
00389    // Extract the acceleration test results first
00390    selfTest[0] = (rawData[0] >> 3) | (rawData[3] & 0x30) >> 4 ; // XA_TEST result is a five-bit unsigned integer
00391    selfTest[1] = (rawData[1] >> 3) | (rawData[3] & 0x0C) >> 4 ; // YA_TEST result is a five-bit unsigned integer
00392    selfTest[2] = (rawData[2] >> 3) | (rawData[3] & 0x03) >> 4 ; // ZA_TEST result is a five-bit unsigned integer
00393    // Extract the gyration test results first
00394    selfTest[3] = rawData[0]  & 0x1F ; // XG_TEST result is a five-bit unsigned integer
00395    selfTest[4] = rawData[1]  & 0x1F ; // YG_TEST result is a five-bit unsigned integer
00396    selfTest[5] = rawData[2]  & 0x1F ; // ZG_TEST result is a five-bit unsigned integer   
00397    // Process results to allow final comparison with factory set values
00398    factoryTrim[0] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[0] - 1.0f)/30.0f))); // FT[Xa] factory trim calculation
00399    factoryTrim[1] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[1] - 1.0f)/30.0f))); // FT[Ya] factory trim calculation
00400    factoryTrim[2] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[2] - 1.0f)/30.0f))); // FT[Za] factory trim calculation
00401    factoryTrim[3] =  ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[3] - 1.0f) ));             // FT[Xg] factory trim calculation
00402    factoryTrim[4] =  (-25.0f*131.0f)*(pow( 1.046f , (selfTest[4] - 1.0f) ));             // FT[Yg] factory trim calculation
00403    factoryTrim[5] =  ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[5] - 1.0f) ));             // FT[Zg] factory trim calculation
00404    
00405  //  Output self-test results and factory trim calculation if desired
00406  //  Serial.println(selfTest[0]); Serial.println(selfTest[1]); Serial.println(selfTest[2]);
00407  //  Serial.println(selfTest[3]); Serial.println(selfTest[4]); Serial.println(selfTest[5]);
00408  //  Serial.println(factoryTrim[0]); Serial.println(factoryTrim[1]); Serial.println(factoryTrim[2]);
00409  //  Serial.println(factoryTrim[3]); Serial.println(factoryTrim[4]); Serial.println(factoryTrim[5]);
00410 
00411  // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response
00412  // To get to percent, must multiply by 100 and subtract result from 100
00413    for (int i = 0; i < 6; i++) {
00414      destination[i] = 100.0f + 100.0f*(selfTest[i] - factoryTrim[i])/factoryTrim[i]; // Report percent differences
00415    }
00416    
00417 }
00418 
00419 
00420 // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays"
00421 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details)
00422 // which fuses acceleration and rotation rate to produce a quaternion-based estimate of relative
00423 // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc.
00424 // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms
00425 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz!
00426         void mpu6050::MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz)
00427         {
00428             float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3];         // short name local variable for readability
00429             float norm;                                               // vector norm
00430             float f1, f2, f3;                                         // objective funcyion elements
00431             float J_11or24, J_12or23, J_13or22, J_14or21, J_32, J_33; // objective function Jacobian elements
00432             float qDot1, qDot2, qDot3, qDot4;
00433             float hatDot1, hatDot2, hatDot3, hatDot4;
00434             float gerrx, gerry, gerrz, gbiasx, gbiasy, gbiasz;  // gyro bias error
00435 
00436             // Auxiliary variables to avoid repeated arithmetic
00437             float _halfq1 = 0.5f * q1;
00438             float _halfq2 = 0.5f * q2;
00439             float _halfq3 = 0.5f * q3;
00440             float _halfq4 = 0.5f * q4;
00441             float _2q1 = 2.0f * q1;
00442             float _2q2 = 2.0f * q2;
00443             float _2q3 = 2.0f * q3;
00444             float _2q4 = 2.0f * q4;
00445 //            float _2q1q3 = 2.0f * q1 * q3;
00446 //            float _2q3q4 = 2.0f * q3 * q4;
00447 
00448             // Normalise accelerometer measurement
00449             norm = sqrt(ax * ax + ay * ay + az * az);
00450             if (norm == 0.0f) return; // handle NaN
00451             norm = 1.0f/norm;
00452             ax *= norm;
00453             ay *= norm;
00454             az *= norm;
00455             
00456             // Compute the objective function and Jacobian
00457             f1 = _2q2 * q4 - _2q1 * q3 - ax;
00458             f2 = _2q1 * q2 + _2q3 * q4 - ay;
00459             f3 = 1.0f - _2q2 * q2 - _2q3 * q3 - az;
00460             J_11or24 = _2q3;
00461             J_12or23 = _2q4;
00462             J_13or22 = _2q1;
00463             J_14or21 = _2q2;
00464             J_32 = 2.0f * J_14or21;
00465             J_33 = 2.0f * J_11or24;
00466           
00467             // Compute the gradient (matrix multiplication)
00468             hatDot1 = J_14or21 * f2 - J_11or24 * f1;
00469             hatDot2 = J_12or23 * f1 + J_13or22 * f2 - J_32 * f3;
00470             hatDot3 = J_12or23 * f2 - J_33 *f3 - J_13or22 * f1;
00471             hatDot4 = J_14or21 * f1 + J_11or24 * f2;
00472             
00473             // Normalize the gradient
00474             norm = sqrt(hatDot1 * hatDot1 + hatDot2 * hatDot2 + hatDot3 * hatDot3 + hatDot4 * hatDot4);
00475             hatDot1 /= norm;
00476             hatDot2 /= norm;
00477             hatDot3 /= norm;
00478             hatDot4 /= norm;
00479             
00480             // Compute estimated gyroscope biases
00481             gerrx = _2q1 * hatDot2 - _2q2 * hatDot1 - _2q3 * hatDot4 + _2q4 * hatDot3;
00482             gerry = _2q1 * hatDot3 + _2q2 * hatDot4 - _2q3 * hatDot1 - _2q4 * hatDot2;
00483             gerrz = _2q1 * hatDot4 - _2q2 * hatDot3 + _2q3 * hatDot2 - _2q4 * hatDot1;
00484             
00485             // Compute and remove gyroscope biases
00486             gbiasx += gerrx * deltat * zeta;
00487             gbiasy += gerry * deltat * zeta;
00488             gbiasz += gerrz * deltat * zeta;
00489  //           gx -= gbiasx;
00490  //           gy -= gbiasy;
00491  //           gz -= gbiasz;
00492             
00493             // Compute the quaternion derivative
00494             qDot1 = -_halfq2 * gx - _halfq3 * gy - _halfq4 * gz;
00495             qDot2 =  _halfq1 * gx + _halfq3 * gz - _halfq4 * gy;
00496             qDot3 =  _halfq1 * gy - _halfq2 * gz + _halfq4 * gx;
00497             qDot4 =  _halfq1 * gz + _halfq2 * gy - _halfq3 * gx;
00498 
00499             // Compute then integrate estimated quaternion derivative
00500             q1 += (qDot1 -(beta * hatDot1)) * deltat;
00501             q2 += (qDot2 -(beta * hatDot2)) * deltat;
00502             q3 += (qDot3 -(beta * hatDot3)) * deltat;
00503             q4 += (qDot4 -(beta * hatDot4)) * deltat;
00504 
00505             // Normalize the quaternion
00506             norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);    // normalise quaternion
00507             norm = 1.0f/norm;
00508             q[0] = q1 * norm;
00509             q[1] = q2 * norm;
00510             q[2] = q3 * norm;
00511             q[3] = q4 * norm;
00512             
00513         }