MPU9250 library fork

Dependents:   IMU_serial

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers MPU9250.h Source File

MPU9250.h

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