MPU9250 test with polling or ISR

Dependencies:   mbed

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