Basic program to obtain properly-scaled gyro, accelerometer, and magnetometer data from the MPU-9150 9-axis motion sensor. Nine-axis sensor fusion with Sebastian Madgwick's and Mahony's open-source sensor fusion filters running on an STM32F401RE Nucleo board at 84 MHz achieve sensor fusion filter update rates of ~5000 Hz. Additional info at https://github.com/kriswiner/STM32F401.

Dependencies:   ST_401_84MHZ mbed

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers MPU9150.h Source File

MPU9150.h

00001 #ifndef MPU9150_H
00002 #define MPU9150_H
00003  
00004 #include "mbed.h"
00005  
00006 // Define registers per MPU6050, Register Map and Descriptions, Rev 4.2, 08/19/2013 6 DOF Motion sensor fusion device
00007 // Invensense Inc., www.invensense.com
00008 // See also MPU-9150 Register Map and Descriptions, Revision 4.0, RM-MPU-9150A-00, 9/12/2012 for registers not listed in 
00009 // above document; the MPU6050 and MPU 9150 are virtually identical but the latter has an on-board magnetic sensor
00010 //
00011 //Magnetometer Registers
00012 #define WHO_AM_I_AK8975A 0x00 // should return 0x48
00013 #define INFO             0x01
00014 #define AK8975A_ST1      0x02  // data ready status bit 0
00015 #define AK8975A_ADDRESS  0x0C<<1
00016 #define AK8975A_XOUT_L   0x03  // data
00017 #define AK8975A_XOUT_H   0x04
00018 #define AK8975A_YOUT_L   0x05
00019 #define AK8975A_YOUT_H   0x06
00020 #define AK8975A_ZOUT_L   0x07
00021 #define AK8975A_ZOUT_H   0x08
00022 #define AK8975A_ST2      0x09  // Data overflow bit 3 and data read error status bit 2
00023 #define AK8975A_CNTL     0x0A  // Power down (0000), single-measurement (0001), self-test (1000) and Fuse ROM (1111) modes on bits 3:0
00024 #define AK8975A_ASTC     0x0C  // Self test control
00025 #define AK8975A_ASAX     0x10  // Fuse ROM x-axis sensitivity adjustment value
00026 #define AK8975A_ASAY     0x11  // Fuse ROM y-axis sensitivity adjustment value
00027 #define AK8975A_ASAZ     0x12  // Fuse ROM z-axis sensitivity adjustment value
00028 
00029 #define XGOFFS_TC        0x00 // Bit 7 PWR_MODE, bits 6:1 XG_OFFS_TC, bit 0 OTP_BNK_VLD                 
00030 #define YGOFFS_TC        0x01                                                                          
00031 #define ZGOFFS_TC        0x02
00032 #define X_FINE_GAIN      0x03 // [7:0] fine gain
00033 #define Y_FINE_GAIN      0x04
00034 #define Z_FINE_GAIN      0x05
00035 #define XA_OFFSET_H      0x06 // User-defined trim values for accelerometer
00036 #define XA_OFFSET_L_TC   0x07
00037 #define YA_OFFSET_H      0x08
00038 #define YA_OFFSET_L_TC   0x09
00039 #define ZA_OFFSET_H      0x0A
00040 #define ZA_OFFSET_L_TC   0x0B
00041 #define SELF_TEST_X      0x0D
00042 #define SELF_TEST_Y      0x0E    
00043 #define SELF_TEST_Z      0x0F
00044 #define SELF_TEST_A      0x10
00045 #define XG_OFFS_USRH     0x13  // User-defined trim values for gyroscope, populate with calibration routine
00046 #define XG_OFFS_USRL     0x14
00047 #define YG_OFFS_USRH     0x15
00048 #define YG_OFFS_USRL     0x16
00049 #define ZG_OFFS_USRH     0x17
00050 #define ZG_OFFS_USRL     0x18
00051 #define SMPLRT_DIV       0x19
00052 #define CONFIG           0x1A
00053 #define GYRO_CONFIG      0x1B
00054 #define ACCEL_CONFIG     0x1C
00055 #define FF_THR           0x1D  // Free-fall
00056 #define FF_DUR           0x1E  // Free-fall
00057 #define MOT_THR          0x1F  // Motion detection threshold bits [7:0]
00058 #define MOT_DUR          0x20  // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms
00059 #define ZMOT_THR         0x21  // Zero-motion detection threshold bits [7:0]
00060 #define ZRMOT_DUR        0x22  // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms
00061 #define FIFO_EN          0x23
00062 #define I2C_MST_CTRL     0x24   
00063 #define I2C_SLV0_ADDR    0x25
00064 #define I2C_SLV0_REG     0x26
00065 #define I2C_SLV0_CTRL    0x27
00066 #define I2C_SLV1_ADDR    0x28
00067 #define I2C_SLV1_REG     0x29
00068 #define I2C_SLV1_CTRL    0x2A
00069 #define I2C_SLV2_ADDR    0x2B
00070 #define I2C_SLV2_REG     0x2C
00071 #define I2C_SLV2_CTRL    0x2D
00072 #define I2C_SLV3_ADDR    0x2E
00073 #define I2C_SLV3_REG     0x2F
00074 #define I2C_SLV3_CTRL    0x30
00075 #define I2C_SLV4_ADDR    0x31
00076 #define I2C_SLV4_REG     0x32
00077 #define I2C_SLV4_DO      0x33
00078 #define I2C_SLV4_CTRL    0x34
00079 #define I2C_SLV4_DI      0x35
00080 #define I2C_MST_STATUS   0x36
00081 #define INT_PIN_CFG      0x37
00082 #define INT_ENABLE       0x38
00083 #define DMP_INT_STATUS   0x39  // Check DMP interrupt
00084 #define INT_STATUS       0x3A
00085 #define ACCEL_XOUT_H     0x3B
00086 #define ACCEL_XOUT_L     0x3C
00087 #define ACCEL_YOUT_H     0x3D
00088 #define ACCEL_YOUT_L     0x3E
00089 #define ACCEL_ZOUT_H     0x3F
00090 #define ACCEL_ZOUT_L     0x40
00091 #define TEMP_OUT_H       0x41
00092 #define TEMP_OUT_L       0x42
00093 #define GYRO_XOUT_H      0x43
00094 #define GYRO_XOUT_L      0x44
00095 #define GYRO_YOUT_H      0x45
00096 #define GYRO_YOUT_L      0x46
00097 #define GYRO_ZOUT_H      0x47
00098 #define GYRO_ZOUT_L      0x48
00099 #define EXT_SENS_DATA_00 0x49
00100 #define EXT_SENS_DATA_01 0x4A
00101 #define EXT_SENS_DATA_02 0x4B
00102 #define EXT_SENS_DATA_03 0x4C
00103 #define EXT_SENS_DATA_04 0x4D
00104 #define EXT_SENS_DATA_05 0x4E
00105 #define EXT_SENS_DATA_06 0x4F
00106 #define EXT_SENS_DATA_07 0x50
00107 #define EXT_SENS_DATA_08 0x51
00108 #define EXT_SENS_DATA_09 0x52
00109 #define EXT_SENS_DATA_10 0x53
00110 #define EXT_SENS_DATA_11 0x54
00111 #define EXT_SENS_DATA_12 0x55
00112 #define EXT_SENS_DATA_13 0x56
00113 #define EXT_SENS_DATA_14 0x57
00114 #define EXT_SENS_DATA_15 0x58
00115 #define EXT_SENS_DATA_16 0x59
00116 #define EXT_SENS_DATA_17 0x5A
00117 #define EXT_SENS_DATA_18 0x5B
00118 #define EXT_SENS_DATA_19 0x5C
00119 #define EXT_SENS_DATA_20 0x5D
00120 #define EXT_SENS_DATA_21 0x5E
00121 #define EXT_SENS_DATA_22 0x5F
00122 #define EXT_SENS_DATA_23 0x60
00123 #define MOT_DETECT_STATUS 0x61
00124 #define I2C_SLV0_DO      0x63
00125 #define I2C_SLV1_DO      0x64
00126 #define I2C_SLV2_DO      0x65
00127 #define I2C_SLV3_DO      0x66
00128 #define I2C_MST_DELAY_CTRL 0x67
00129 #define SIGNAL_PATH_RESET  0x68
00130 #define MOT_DETECT_CTRL   0x69
00131 #define USER_CTRL        0x6A  // Bit 7 enable DMP, bit 3 reset DMP
00132 #define PWR_MGMT_1       0x6B // Device defaults to the SLEEP mode
00133 #define PWR_MGMT_2       0x6C
00134 #define DMP_BANK         0x6D  // Activates a specific bank in the DMP
00135 #define DMP_RW_PNT       0x6E  // Set read/write pointer to a specific start address in specified DMP bank
00136 #define DMP_REG          0x6F  // Register in DMP from which to read or to which to write
00137 #define DMP_REG_1        0x70
00138 #define DMP_REG_2        0x71
00139 #define FIFO_COUNTH      0x72
00140 #define FIFO_COUNTL      0x73
00141 #define FIFO_R_W         0x74
00142 #define WHO_AM_I_MPU9150 0x75 // Should return 0x68
00143 
00144 
00145 // Using the GY-9150 breakout board, ADO is set to 0 
00146 // Seven-bit device address is 110100 for ADO = 0 and 110101 for ADO = 1
00147 // mbed uses the eight-bit device address, so shift seven-bit addresses left by one!
00148 #define ADO 0
00149 #if ADO
00150 #define MPU9150_ADDRESS 0x69<<1  // Device address when ADO = 1
00151 #else
00152 #define MPU9150_ADDRESS 0x68<<1  // Device address when ADO = 0
00153 #endif  
00154 
00155 // Set initial input parameters
00156 enum Ascale {
00157   AFS_2G = 0,
00158   AFS_4G,
00159   AFS_8G,
00160   AFS_16G
00161 };
00162 
00163 enum Gscale {
00164   GFS_250DPS = 0,
00165   GFS_500DPS,
00166   GFS_1000DPS,
00167   GFS_2000DPS
00168 };
00169 
00170 uint8_t Ascale = AFS_2G;     // AFS_2G, AFS_4G, AFS_8G, AFS_16G
00171 uint8_t Gscale = GFS_250DPS; // GFS_250DPS, GFS_500DPS, GFS_1000DPS, GFS_2000DPS
00172 float aRes, gRes, mRes;      // scale resolutions per LSB for the sensors
00173 
00174 //Set up I2C, (SDA,SCL)
00175 I2C i2c(I2C_SDA, I2C_SCL);
00176 
00177 DigitalOut myled(LED1);
00178     
00179 // Pin definitions
00180 int intPin = 12;  // These can be changed, 2 and 3 are the Arduinos ext int pins
00181 
00182 int16_t accelCount[3];  // Stores the 16-bit signed accelerometer sensor output
00183 int16_t gyroCount[3];   // Stores the 16-bit signed gyro sensor output
00184 int16_t magCount[3];    // Stores the 16-bit signed magnetometer sensor output
00185 float magCalibration[3] = {0, 0, 0}, magbias[3] = {0, 0, 0};  // Factory mag calibration and mag bias
00186 float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer
00187 float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values 
00188 int16_t tempCount;   // Stores the real internal chip temperature in degrees Celsius
00189 float temperature;
00190 float SelfTest[6];
00191 
00192 int delt_t = 0; // used to control display output rate
00193 int count = 0;  // used to control display output rate
00194 
00195 // parameters for 6 DoF sensor fusion calculations
00196 float PI = 3.14159265358979323846f;
00197 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
00198 float beta = sqrt(3.0f / 4.0f) * GyroMeasError;  // compute beta
00199 float GyroMeasDrift = PI * (1.0f / 180.0f);      // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s)
00200 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
00201 #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
00202 #define Ki 0.0f
00203 
00204 float pitch, yaw, roll;
00205 float deltat = 0.0f;                             // integration interval for both filter schemes
00206 int lastUpdate = 0, firstUpdate = 0, Now = 0;    // used to calculate integration interval                               // used to calculate integration interval
00207 float q[4] = {1.0f, 0.0f, 0.0f, 0.0f};           // vector to hold quaternion
00208 float eInt[3] = {0.0f, 0.0f, 0.0f};              // vector to hold integral error for Mahony method
00209 
00210 class MPU9150 {
00211  
00212     protected:
00213  
00214     public:
00215   //===================================================================================================================
00216 //====== Set of useful function to access acceleratio, gyroscope, and temperature data
00217 //===================================================================================================================
00218 
00219     void writeByte(uint8_t address, uint8_t subAddress, uint8_t data)
00220 {
00221    char data_write[2];
00222    data_write[0] = subAddress;
00223    data_write[1] = data;
00224    i2c.write(address, data_write, 2, 0);
00225 }
00226 
00227     char readByte(uint8_t address, uint8_t subAddress)
00228 {
00229     char data[1]; // `data` will store the register data     
00230     char data_write[1];
00231     data_write[0] = subAddress;
00232     i2c.write(address, data_write, 1, 1); // no stop
00233     i2c.read(address, data, 1, 0); 
00234     return data[0]; 
00235 }
00236 
00237     void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest)
00238 {     
00239     char data[14];
00240     char data_write[1];
00241     data_write[0] = subAddress;
00242     i2c.write(address, data_write, 1, 1); // no stop
00243     i2c.read(address, data, count, 0); 
00244     for(int ii = 0; ii < count; ii++) {
00245      dest[ii] = data[ii];
00246     }
00247 } 
00248  
00249 
00250 void getGres() {
00251   switch (Gscale)
00252   {
00253     // Possible gyro scales (and their register bit settings) are:
00254     // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS  (11). 
00255         // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
00256     case GFS_250DPS:
00257           gRes = 250.0/32768.0;
00258           break;
00259     case GFS_500DPS:
00260           gRes = 500.0/32768.0;
00261           break;
00262     case GFS_1000DPS:
00263           gRes = 1000.0/32768.0;
00264           break;
00265     case GFS_2000DPS:
00266           gRes = 2000.0/32768.0;
00267           break;
00268   }
00269 }
00270 
00271 
00272 void getAres() {
00273   switch (Ascale)
00274   {
00275     // Possible accelerometer scales (and their register bit settings) are:
00276     // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs  (11). 
00277         // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
00278     case AFS_2G:
00279           aRes = 2.0/32768.0;
00280           break;
00281     case AFS_4G:
00282           aRes = 4.0/32768.0;
00283           break;
00284     case AFS_8G:
00285           aRes = 8.0/32768.0;
00286           break;
00287     case AFS_16G:
00288           aRes = 16.0/32768.0;
00289           break;
00290   }
00291 }
00292 
00293 
00294 void readAccelData(int16_t * destination)
00295 {
00296   uint8_t rawData[6];  // x/y/z accel register data stored here
00297   readBytes(MPU9150_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]);  // Read the six raw data registers into data array
00298   destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ;  // Turn the MSB and LSB into a signed 16-bit value
00299   destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;  
00300   destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 
00301 }
00302 
00303 void readGyroData(int16_t * destination)
00304 {
00305   uint8_t rawData[6];  // x/y/z gyro register data stored here
00306   readBytes(MPU9150_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]);  // Read the six raw data registers sequentially into data array
00307   destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ;  // Turn the MSB and LSB into a signed 16-bit value
00308   destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;  
00309   destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 
00310 }
00311 
00312 void readMagData(int16_t * destination)
00313 {
00314   uint8_t rawData[6];  // x/y/z gyro register data stored here
00315   writeByte(AK8975A_ADDRESS, AK8975A_CNTL, 0x01); // toggle enable data read from magnetometer, no continuous read mode!
00316   wait(0.01);
00317   // Only accept a new magnetometer data read if the data ready bit is set and 
00318   // if there are no sensor overflow or data read errors
00319   if(readByte(AK8975A_ADDRESS, AK8975A_ST1) & 0x01) { // wait for magnetometer data ready bit to be set
00320   readBytes(AK8975A_ADDRESS, AK8975A_XOUT_L, 6, &rawData[0]);  // Read the six raw data registers sequentially into data array
00321   destination[0] = ((int16_t)rawData[1] << 8) | rawData[0] ;  // Turn the MSB and LSB into a signed 16-bit value
00322   destination[1] = ((int16_t)rawData[3] << 8) | rawData[2] ;  
00323   destination[2] = ((int16_t)rawData[5] << 8) | rawData[4] ; 
00324   }
00325 }
00326 
00327 void initAK8975A(float * destination)
00328 {
00329   uint8_t rawData[3];  // x/y/z gyro register data stored here
00330   writeByte(AK8975A_ADDRESS, AK8975A_CNTL, 0x00); // Power down
00331   wait(0.01);
00332   writeByte(AK8975A_ADDRESS, AK8975A_CNTL, 0x0F); // Enter Fuse ROM access mode
00333   wait(0.01);
00334   readBytes(AK8975A_ADDRESS, AK8975A_ASAX, 3, &rawData[0]);  // Read the x-, y-, and z-axis calibration values
00335   destination[0] =  (float)(rawData[0] - 128)/256.0f + 1.0f; // Return x-axis sensitivity adjustment values
00336   destination[1] =  (float)(rawData[1] - 128)/256.0f + 1.0f;  
00337   destination[2] =  (float)(rawData[2] - 128)/256.0f + 1.0f; 
00338 }
00339 
00340 int16_t readTempData()
00341 {
00342   uint8_t rawData[2];  // x/y/z gyro register data stored here
00343   readBytes(MPU9150_ADDRESS, TEMP_OUT_H, 2, &rawData[0]);  // Read the two raw data registers sequentially into data array 
00344   return ((int16_t)rawData[0] << 8) | rawData[1] ;  // Turn the MSB and LSB into a 16-bit value
00345 }
00346 
00347 void resetMPU9150() {
00348   // reset device
00349   writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
00350   wait(0.1);
00351   }
00352   
00353 
00354 
00355 void initMPU9150()
00356 {  
00357  // Initialize MPU9150 device
00358  // wake up device
00359   writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors 
00360   wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt  
00361 
00362  // get stable time source
00363   writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x01);  // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
00364 
00365  // Configure Gyro and Accelerometer
00366  // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively; 
00367  // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both
00368  // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate
00369   writeByte(MPU9150_ADDRESS, CONFIG, 0x03);  
00370  
00371  // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV)
00372   writeByte(MPU9150_ADDRESS, SMPLRT_DIV, 0x04);  // Use a 200 Hz rate; the same rate set in CONFIG above
00373  
00374  // Set gyroscope full scale range
00375  // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3
00376   uint8_t c =  readByte(MPU9150_ADDRESS, GYRO_CONFIG);
00377   writeByte(MPU9150_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 
00378   writeByte(MPU9150_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3]
00379   writeByte(MPU9150_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro
00380    
00381  // Set accelerometer configuration
00382   c =  readByte(MPU9150_ADDRESS, ACCEL_CONFIG);
00383   writeByte(MPU9150_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 
00384   writeByte(MPU9150_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3]
00385   writeByte(MPU9150_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer 
00386 
00387  // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates, 
00388  // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting
00389 
00390   // Configure Interrupts and Bypass Enable
00391   // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips 
00392   // can join the I2C bus and all can be controlled by the Arduino as master
00393    writeByte(MPU9150_ADDRESS, INT_PIN_CFG, 0x22);    
00394    writeByte(MPU9150_ADDRESS, INT_ENABLE, 0x01);  // Enable data ready (bit 0) interrupt
00395 }
00396 
00397 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average
00398 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers.
00399 void calibrateMPU9150(float * dest1, float * dest2)
00400 {  
00401   uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data
00402   uint16_t ii, packet_count, fifo_count;
00403   int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0};
00404   
00405 // reset device, reset all registers, clear gyro and accelerometer bias registers
00406   writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
00407   wait(0.1);  
00408    
00409 // get stable time source
00410 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
00411   writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x01);  
00412   writeByte(MPU9150_ADDRESS, PWR_MGMT_2, 0x00); 
00413   wait(0.2);
00414   
00415 // Configure device for bias calculation
00416   writeByte(MPU9150_ADDRESS, INT_ENABLE, 0x00);   // Disable all interrupts
00417   writeByte(MPU9150_ADDRESS, FIFO_EN, 0x00);      // Disable FIFO
00418   writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x00);   // Turn on internal clock source
00419   writeByte(MPU9150_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master
00420   writeByte(MPU9150_ADDRESS, USER_CTRL, 0x00);    // Disable FIFO and I2C master modes
00421   writeByte(MPU9150_ADDRESS, USER_CTRL, 0x0C);    // Reset FIFO and DMP
00422   wait(0.015);
00423   
00424 // Configure MPU9150 gyro and accelerometer for bias calculation
00425   writeByte(MPU9150_ADDRESS, CONFIG, 0x01);      // Set low-pass filter to 188 Hz
00426   writeByte(MPU9150_ADDRESS, SMPLRT_DIV, 0x00);  // Set sample rate to 1 kHz
00427   writeByte(MPU9150_ADDRESS, GYRO_CONFIG, 0x00);  // Set gyro full-scale to 250 degrees per second, maximum sensitivity
00428   writeByte(MPU9150_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity
00429  
00430   uint16_t  gyrosensitivity  = 131;   // = 131 LSB/degrees/sec
00431   uint16_t  accelsensitivity = 16384;  // = 16384 LSB/g
00432 
00433 // Configure FIFO to capture accelerometer and gyro data for bias calculation
00434   writeByte(MPU9150_ADDRESS, USER_CTRL, 0x40);   // Enable FIFO  
00435   writeByte(MPU9150_ADDRESS, FIFO_EN, 0x78);     // Enable gyro and accelerometer sensors for FIFO (max size 1024 bytes in MPU9150)
00436   wait(0.08); // accumulate 80 samples in 80 milliseconds = 960 bytes
00437 
00438 // At end of sample accumulation, turn off FIFO sensor read
00439   writeByte(MPU9150_ADDRESS, FIFO_EN, 0x00);        // Disable gyro and accelerometer sensors for FIFO
00440   readBytes(MPU9150_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count
00441   fifo_count = ((uint16_t)data[0] << 8) | data[1];
00442   packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging
00443 
00444   for (ii = 0; ii < packet_count; ii++) {
00445     int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0};
00446     readBytes(MPU9150_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging
00447     accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1]  ) ;  // Form signed 16-bit integer for each sample in FIFO
00448     accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3]  ) ;
00449     accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5]  ) ;    
00450     gyro_temp[0]  = (int16_t) (((int16_t)data[6] << 8) | data[7]  ) ;
00451     gyro_temp[1]  = (int16_t) (((int16_t)data[8] << 8) | data[9]  ) ;
00452     gyro_temp[2]  = (int16_t) (((int16_t)data[10] << 8) | data[11]) ;
00453     
00454     accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases
00455     accel_bias[1] += (int32_t) accel_temp[1];
00456     accel_bias[2] += (int32_t) accel_temp[2];
00457     gyro_bias[0]  += (int32_t) gyro_temp[0];
00458     gyro_bias[1]  += (int32_t) gyro_temp[1];
00459     gyro_bias[2]  += (int32_t) gyro_temp[2];
00460             
00461 }
00462     accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases
00463     accel_bias[1] /= (int32_t) packet_count;
00464     accel_bias[2] /= (int32_t) packet_count;
00465     gyro_bias[0]  /= (int32_t) packet_count;
00466     gyro_bias[1]  /= (int32_t) packet_count;
00467     gyro_bias[2]  /= (int32_t) packet_count;
00468     
00469   if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;}  // Remove gravity from the z-axis accelerometer bias calculation
00470   else {accel_bias[2] += (int32_t) accelsensitivity;}
00471  
00472 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup
00473   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
00474   data[1] = (-gyro_bias[0]/4)       & 0xFF; // Biases are additive, so change sign on calculated average gyro biases
00475   data[2] = (-gyro_bias[1]/4  >> 8) & 0xFF;
00476   data[3] = (-gyro_bias[1]/4)       & 0xFF;
00477   data[4] = (-gyro_bias[2]/4  >> 8) & 0xFF;
00478   data[5] = (-gyro_bias[2]/4)       & 0xFF;
00479 
00480 /// Push gyro biases to hardware registers
00481   writeByte(MPU9150_ADDRESS, XG_OFFS_USRH, data[0]); 
00482   writeByte(MPU9150_ADDRESS, XG_OFFS_USRL, data[1]);
00483   writeByte(MPU9150_ADDRESS, YG_OFFS_USRH, data[2]);
00484   writeByte(MPU9150_ADDRESS, YG_OFFS_USRL, data[3]);
00485   writeByte(MPU9150_ADDRESS, ZG_OFFS_USRH, data[4]);
00486   writeByte(MPU9150_ADDRESS, ZG_OFFS_USRL, data[5]);
00487 
00488   dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction
00489   dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity;
00490   dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity;
00491 
00492 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain
00493 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold
00494 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature
00495 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that
00496 // the accelerometer biases calculated above must be divided by 8.
00497 
00498   int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases
00499   readBytes(MPU9150_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values
00500   accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1];
00501   readBytes(MPU9150_ADDRESS, YA_OFFSET_H, 2, &data[0]);
00502   accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1];
00503   readBytes(MPU9150_ADDRESS, ZA_OFFSET_H, 2, &data[0]);
00504   accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1];
00505   
00506   uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers
00507   uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis
00508   
00509   for(ii = 0; ii < 3; ii++) {
00510     if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit
00511   }
00512 
00513   // Construct total accelerometer bias, including calculated average accelerometer bias from above
00514   accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale)
00515   accel_bias_reg[1] -= (accel_bias[1]/8);
00516   accel_bias_reg[2] -= (accel_bias[2]/8);
00517  
00518   data[0] = (accel_bias_reg[0] >> 8) & 0xFF;
00519   data[1] = (accel_bias_reg[0])      & 0xFF;
00520   data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers
00521   data[2] = (accel_bias_reg[1] >> 8) & 0xFF;
00522   data[3] = (accel_bias_reg[1])      & 0xFF;
00523   data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers
00524   data[4] = (accel_bias_reg[2] >> 8) & 0xFF;
00525   data[5] = (accel_bias_reg[2])      & 0xFF;
00526   data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers
00527 
00528 // Apparently this is not working for the acceleration biases in the MPU-9250
00529 // Are we handling the temperature correction bit properly?
00530 // Push accelerometer biases to hardware registers
00531   writeByte(MPU9150_ADDRESS, XA_OFFSET_H, data[0]);  
00532   writeByte(MPU9150_ADDRESS, XA_OFFSET_L_TC, data[1]);
00533   writeByte(MPU9150_ADDRESS, YA_OFFSET_H, data[2]);
00534   writeByte(MPU9150_ADDRESS, YA_OFFSET_L_TC, data[3]);
00535   writeByte(MPU9150_ADDRESS, ZA_OFFSET_H, data[4]);
00536   writeByte(MPU9150_ADDRESS, ZA_OFFSET_L_TC, data[5]);
00537 
00538 // Output scaled accelerometer biases for manual subtraction in the main program
00539    dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; 
00540    dest2[1] = (float)accel_bias[1]/(float)accelsensitivity;
00541    dest2[2] = (float)accel_bias[2]/(float)accelsensitivity;
00542 }
00543 
00544 
00545 // Accelerometer and gyroscope self test; check calibration wrt factory settings
00546 void MPU9150SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass
00547 {
00548    uint8_t rawData[4] = {0, 0, 0, 0};
00549    uint8_t selfTest[6];
00550    float factoryTrim[6];
00551    
00552    // Configure the accelerometer for self-test
00553    writeByte(MPU9150_ADDRESS, ACCEL_CONFIG, 0xF0); // Enable self test on all three axes and set accelerometer range to +/- 8 g
00554    writeByte(MPU9150_ADDRESS, GYRO_CONFIG,  0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s
00555    wait(0.25);  // Delay a while to let the device execute the self-test
00556    rawData[0] = readByte(MPU9150_ADDRESS, SELF_TEST_X); // X-axis self-test results
00557    rawData[1] = readByte(MPU9150_ADDRESS, SELF_TEST_Y); // Y-axis self-test results
00558    rawData[2] = readByte(MPU9150_ADDRESS, SELF_TEST_Z); // Z-axis self-test results
00559    rawData[3] = readByte(MPU9150_ADDRESS, SELF_TEST_A); // Mixed-axis self-test results
00560    // Extract the acceleration test results first
00561    selfTest[0] = (rawData[0] >> 3) | (rawData[3] & 0x30) >> 4 ; // XA_TEST result is a five-bit unsigned integer
00562    selfTest[1] = (rawData[1] >> 3) | (rawData[3] & 0x0C) >> 4 ; // YA_TEST result is a five-bit unsigned integer
00563    selfTest[2] = (rawData[2] >> 3) | (rawData[3] & 0x03) >> 4 ; // ZA_TEST result is a five-bit unsigned integer
00564    // Extract the gyration test results first
00565    selfTest[3] = rawData[0]  & 0x1F ; // XG_TEST result is a five-bit unsigned integer
00566    selfTest[4] = rawData[1]  & 0x1F ; // YG_TEST result is a five-bit unsigned integer
00567    selfTest[5] = rawData[2]  & 0x1F ; // ZG_TEST result is a five-bit unsigned integer   
00568    // Process results to allow final comparison with factory set values
00569    factoryTrim[0] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[0] - 1.0f)/30.0f))); // FT[Xa] factory trim calculation
00570    factoryTrim[1] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[1] - 1.0f)/30.0f))); // FT[Ya] factory trim calculation
00571    factoryTrim[2] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[2] - 1.0f)/30.0f))); // FT[Za] factory trim calculation
00572    factoryTrim[3] =  ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[3] - 1.0f) ));             // FT[Xg] factory trim calculation
00573    factoryTrim[4] =  (-25.0f*131.0f)*(pow( 1.046f , (selfTest[4] - 1.0f) ));             // FT[Yg] factory trim calculation
00574    factoryTrim[5] =  ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[5] - 1.0f) ));             // FT[Zg] factory trim calculation
00575    
00576  //  Output self-test results and factory trim calculation if desired
00577  //  Serial.println(selfTest[0]); Serial.println(selfTest[1]); Serial.println(selfTest[2]);
00578  //  Serial.println(selfTest[3]); Serial.println(selfTest[4]); Serial.println(selfTest[5]);
00579  //  Serial.println(factoryTrim[0]); Serial.println(factoryTrim[1]); Serial.println(factoryTrim[2]);
00580  //  Serial.println(factoryTrim[3]); Serial.println(factoryTrim[4]); Serial.println(factoryTrim[5]);
00581 
00582  // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response
00583  // To get to percent, must multiply by 100 and subtract result from 100
00584    for (int i = 0; i < 6; i++) {
00585      destination[i] = 100.0f + 100.0f*(selfTest[i] - factoryTrim[i])/factoryTrim[i]; // Report percent differences
00586    }
00587    
00588 }
00589 
00590 
00591 
00592 // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays"
00593 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details)
00594 // which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute
00595 // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc.
00596 // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms
00597 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz!
00598         void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
00599         {
00600             float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3];   // short name local variable for readability
00601             float norm;
00602             float hx, hy, _2bx, _2bz;
00603             float s1, s2, s3, s4;
00604             float qDot1, qDot2, qDot3, qDot4;
00605 
00606             // Auxiliary variables to avoid repeated arithmetic
00607             float _2q1mx;
00608             float _2q1my;
00609             float _2q1mz;
00610             float _2q2mx;
00611             float _4bx;
00612             float _4bz;
00613             float _2q1 = 2.0f * q1;
00614             float _2q2 = 2.0f * q2;
00615             float _2q3 = 2.0f * q3;
00616             float _2q4 = 2.0f * q4;
00617             float _2q1q3 = 2.0f * q1 * q3;
00618             float _2q3q4 = 2.0f * q3 * q4;
00619             float q1q1 = q1 * q1;
00620             float q1q2 = q1 * q2;
00621             float q1q3 = q1 * q3;
00622             float q1q4 = q1 * q4;
00623             float q2q2 = q2 * q2;
00624             float q2q3 = q2 * q3;
00625             float q2q4 = q2 * q4;
00626             float q3q3 = q3 * q3;
00627             float q3q4 = q3 * q4;
00628             float q4q4 = q4 * q4;
00629 
00630             // Normalise accelerometer measurement
00631             norm = sqrt(ax * ax + ay * ay + az * az);
00632             if (norm == 0.0f) return; // handle NaN
00633             norm = 1.0f/norm;
00634             ax *= norm;
00635             ay *= norm;
00636             az *= norm;
00637 
00638             // Normalise magnetometer measurement
00639             norm = sqrt(mx * mx + my * my + mz * mz);
00640             if (norm == 0.0f) return; // handle NaN
00641             norm = 1.0f/norm;
00642             mx *= norm;
00643             my *= norm;
00644             mz *= norm;
00645 
00646             // Reference direction of Earth's magnetic field
00647             _2q1mx = 2.0f * q1 * mx;
00648             _2q1my = 2.0f * q1 * my;
00649             _2q1mz = 2.0f * q1 * mz;
00650             _2q2mx = 2.0f * q2 * mx;
00651             hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4;
00652             hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4;
00653             _2bx = sqrt(hx * hx + hy * hy);
00654             _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4;
00655             _4bx = 2.0f * _2bx;
00656             _4bz = 2.0f * _2bz;
00657 
00658             // Gradient decent algorithm corrective step
00659             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);
00660             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);
00661             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);
00662             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);
00663             norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4);    // normalise step magnitude
00664             norm = 1.0f/norm;
00665             s1 *= norm;
00666             s2 *= norm;
00667             s3 *= norm;
00668             s4 *= norm;
00669 
00670             // Compute rate of change of quaternion
00671             qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1;
00672             qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2;
00673             qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3;
00674             qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4;
00675 
00676             // Integrate to yield quaternion
00677             q1 += qDot1 * deltat;
00678             q2 += qDot2 * deltat;
00679             q3 += qDot3 * deltat;
00680             q4 += qDot4 * deltat;
00681             norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);    // normalise quaternion
00682             norm = 1.0f/norm;
00683             q[0] = q1 * norm;
00684             q[1] = q2 * norm;
00685             q[2] = q3 * norm;
00686             q[3] = q4 * norm;
00687 
00688         }
00689   
00690   
00691   
00692  // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and
00693  // measured ones. 
00694             void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
00695         {
00696             float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3];   // short name local variable for readability
00697             float norm;
00698             float hx, hy, bx, bz;
00699             float vx, vy, vz, wx, wy, wz;
00700             float ex, ey, ez;
00701             float pa, pb, pc;
00702 
00703             // Auxiliary variables to avoid repeated arithmetic
00704             float q1q1 = q1 * q1;
00705             float q1q2 = q1 * q2;
00706             float q1q3 = q1 * q3;
00707             float q1q4 = q1 * q4;
00708             float q2q2 = q2 * q2;
00709             float q2q3 = q2 * q3;
00710             float q2q4 = q2 * q4;
00711             float q3q3 = q3 * q3;
00712             float q3q4 = q3 * q4;
00713             float q4q4 = q4 * q4;   
00714 
00715             // Normalise accelerometer measurement
00716             norm = sqrt(ax * ax + ay * ay + az * az);
00717             if (norm == 0.0f) return; // handle NaN
00718             norm = 1.0f / norm;        // use reciprocal for division
00719             ax *= norm;
00720             ay *= norm;
00721             az *= norm;
00722 
00723             // Normalise magnetometer measurement
00724             norm = sqrt(mx * mx + my * my + mz * mz);
00725             if (norm == 0.0f) return; // handle NaN
00726             norm = 1.0f / norm;        // use reciprocal for division
00727             mx *= norm;
00728             my *= norm;
00729             mz *= norm;
00730 
00731             // Reference direction of Earth's magnetic field
00732             hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3);
00733             hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2);
00734             bx = sqrt((hx * hx) + (hy * hy));
00735             bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3);
00736 
00737             // Estimated direction of gravity and magnetic field
00738             vx = 2.0f * (q2q4 - q1q3);
00739             vy = 2.0f * (q1q2 + q3q4);
00740             vz = q1q1 - q2q2 - q3q3 + q4q4;
00741             wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3);
00742             wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4);
00743             wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3);  
00744 
00745             // Error is cross product between estimated direction and measured direction of gravity
00746             ex = (ay * vz - az * vy) + (my * wz - mz * wy);
00747             ey = (az * vx - ax * vz) + (mz * wx - mx * wz);
00748             ez = (ax * vy - ay * vx) + (mx * wy - my * wx);
00749             if (Ki > 0.0f)
00750             {
00751                 eInt[0] += ex;      // accumulate integral error
00752                 eInt[1] += ey;
00753                 eInt[2] += ez;
00754             }
00755             else
00756             {
00757                 eInt[0] = 0.0f;     // prevent integral wind up
00758                 eInt[1] = 0.0f;
00759                 eInt[2] = 0.0f;
00760             }
00761 
00762             // Apply feedback terms
00763             gx = gx + Kp * ex + Ki * eInt[0];
00764             gy = gy + Kp * ey + Ki * eInt[1];
00765             gz = gz + Kp * ez + Ki * eInt[2];
00766 
00767             // Integrate rate of change of quaternion
00768             pa = q2;
00769             pb = q3;
00770             pc = q4;
00771             q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat);
00772             q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat);
00773             q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat);
00774             q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat);
00775 
00776             // Normalise quaternion
00777             norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);
00778             norm = 1.0f / norm;
00779             q[0] = q1 * norm;
00780             q[1] = q2 * norm;
00781             q[2] = q3 * norm;
00782             q[3] = q4 * norm;
00783  
00784         }
00785   };
00786 #endif