Kris Winer / MPU9250AHRS_nRF52832

Dependencies:   BLE_API mbed-src nRF51822

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers MPU9250.h Source File

MPU9250.h

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