Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
MPU9250.h
00001 //------------------------------------------------------------------------------ 00002 // Attitude measurement using IMU(MPU-9250) 00003 //------------------------------------------------------------------------------ 00004 #ifndef MPU9250_H 00005 #define MPU9250_H 00006 00007 #include "mbed.h" 00008 #include "math.h" 00009 00010 //Magnetometer Registers 00011 #define AK8963_ADDRESS 0x0C<<1 00012 #define WHO_AM_I_AK8963 0x00 // should return 0x48 00013 #define INFO 0x01 00014 #define AK8963_ST1 0x02 // data ready status bit 0 00015 #define AK8963_XOUT_L 0x03 // data 00016 #define AK8963_XOUT_H 0x04 00017 #define AK8963_YOUT_L 0x05 00018 #define AK8963_YOUT_H 0x06 00019 #define AK8963_ZOUT_L 0x07 00020 #define AK8963_ZOUT_H 0x08 00021 #define AK8963_ST2 0x09 // Data overflow bit 3 and data read error status bit 2 00022 #define AK8963_CNTL 0x0A // Power down (0000), single-measurement (0001), self-test (1000) and Fuse ROM (1111) modes on bits 3:0 00023 #define AK8963_ASTC 0x0C // Self test control 00024 #define AK8963_I2CDIS 0x0F // I2C disable 00025 #define AK8963_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value 00026 #define AK8963_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value 00027 #define AK8963_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value 00028 00029 #define SELF_TEST_X_GYRO 0x00 00030 #define SELF_TEST_Y_GYRO 0x01 00031 #define SELF_TEST_Z_GYRO 0x02 00032 00033 /* 00034 #define X_FINE_GAIN 0x03 // [7:0] fine gain 00035 #define Y_FINE_GAIN 0x04 00036 #define Z_FINE_GAIN 0x05 00037 #define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer 00038 #define XA_OFFSET_L_TC 0x07 00039 #define YA_OFFSET_H 0x08 00040 #define YA_OFFSET_L_TC 0x09 00041 #define ZA_OFFSET_H 0x0A 00042 #define ZA_OFFSET_L_TC 0x0B 00043 */ 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 // Seven-bit device address is 110100 for ADO = 0 and 110101 for ADO = 1 00159 //mbed uses the eight-bit device address, so shift seven-bit addresses left by one! 00160 #define ADO 0 00161 #if ADO 00162 #define MPU9250_ADDRESS 0x69<<1 // Device address when ADO = 1 00163 #else 00164 #define MPU9250_ADDRESS 0x68<<1 // Device address when ADO = 0 00165 #endif 00166 00167 // Set initial input parameters 00168 enum Ascale { 00169 AFS_2G = 0, 00170 AFS_4G, 00171 AFS_8G, 00172 AFS_16G 00173 }; 00174 00175 enum Gscale { 00176 GFS_250DPS = 0, 00177 GFS_500DPS, 00178 GFS_1000DPS, 00179 GFS_2000DPS 00180 }; 00181 00182 enum Mscale { 00183 MFS_14BITS = 0, // 0.6 mG per LSB 00184 MFS_16BITS // 0.15 mG per LSB 00185 }; 00186 00187 uint8_t Ascale = AFS_2G; // AFS_2G, AFS_4G, AFS_8G, AFS_16G 00188 uint8_t Gscale = GFS_250DPS; // GFS_250DPS, GFS_500DPS, GFS_1000DPS, GFS_2000DPS 00189 uint8_t Mscale = MFS_16BITS; // MFS_14BITS or MFS_16BITS, 14-bit or 16-bit magnetometer resolution 00190 uint8_t Mmode = 0x06; // Either 8 Hz 0x02) or 100 Hz (0x06) magnetometer data ODR 00191 float aRes, gRes, mRes; // scale resolutions per LSB for the sensors 00192 00193 //Set up I2C, (SDA,SCL) 00194 I2C i2c(p9, p10); 00195 00196 // Pin definitions 00197 int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output 00198 int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output 00199 int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output 00200 float magCalibration[3] = {0, 0, 0}, magbias[3] = {0, 0, 0}; // Factory mag calibration and mag bias 00201 float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer 00202 float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values 00203 float th_ax, th_ay, th_az; 00204 float th_ax_LPF, th_ay_LPF, th_az_LPF; 00205 float pre_th_ax, pre_th_ay, pre_th_az; 00206 float th_gx, th_gy, th_gz; 00207 float pre_gx, pre_gy, pre_gz; 00208 float th_x, th_y, th_z, th_x_d, th_y_d, th_z_d; 00209 int16_t tempCount; // Stores the real internal chip temperature in degrees Celsius 00210 float temperature; 00211 float SelfTest[6]; 00212 00213 float delt_t = 0.0f; // used to display output rate 00214 float sum_dt = 0.0f; // 00215 float dt0_ekf, dt1_ekf, dt0_mwf, dt1_mwf; 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 = sqrt(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 = sqrt(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 pre_pitch, pre_roll; 00228 float lastUpdate = 0.0f, firstUpdate = 0.0f, Now = 0.0f; // 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 q1 = 1.0f; 00231 float q2 = 0.0f; 00232 float q3 = 0.0f; 00233 float q4 = 0.0f; 00234 float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method 00235 00236 class MPU9250 { 00237 00238 protected: 00239 00240 public: 00241 //=================================================================================================================== 00242 //====== Set of useful function to access acceleratio, gyroscope, and temperature data 00243 //=================================================================================================================== 00244 00245 void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) 00246 { 00247 char data_write[2]; 00248 data_write[0] = subAddress; 00249 data_write[1] = data; 00250 i2c.write(address, data_write, 2, 0); 00251 } 00252 00253 char readByte(uint8_t address, uint8_t subAddress) 00254 { 00255 char data[1]; // `data` will store the register data 00256 char data_write[1]; 00257 data_write[0] = subAddress; 00258 i2c.write(address, data_write, 1, 1); // no stop 00259 i2c.read(address, data, 1, 0); 00260 return data[0]; 00261 } 00262 00263 void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) 00264 { 00265 char data[14]; 00266 char data_write[1]; 00267 data_write[0] = subAddress; 00268 i2c.write(address, data_write, 1, 1); // no stop 00269 i2c.read(address, data, count, 0); 00270 for(int ii = 0; ii < count; ii++) { 00271 dest[ii] = data[ii]; 00272 } 00273 } 00274 00275 void getMres() { 00276 switch (Mscale) 00277 { 00278 // Possible magnetometer scales (and their register bit settings) are: 00279 // 14 bit resolution (0) and 16 bit resolution (1) 00280 case MFS_14BITS: 00281 mRes = 10.0*4219.0/8190.0; // Proper scale to return milliGauss 00282 break; 00283 case MFS_16BITS: 00284 mRes = 10.0*4219.0/32760.0; // Proper scale to return milliGauss 00285 break; 00286 } 00287 } 00288 00289 void getGres() { 00290 switch (Gscale) 00291 { 00292 // Possible gyro scales (and their register bit settings) are: 00293 // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11). 00294 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 00295 case GFS_250DPS: 00296 gRes = 250.0/32768.0; 00297 break; 00298 case GFS_500DPS: 00299 gRes = 500.0/32768.0; 00300 break; 00301 case GFS_1000DPS: 00302 gRes = 1000.0/32768.0; 00303 break; 00304 case GFS_2000DPS: 00305 gRes = 2000.0/32768.0; 00306 break; 00307 } 00308 } 00309 00310 void getAres() { 00311 switch (Ascale) 00312 { 00313 // Possible accelerometer scales (and their register bit settings) are: 00314 // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11). 00315 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 00316 case AFS_2G: 00317 aRes = 2.0/32768.0; 00318 break; 00319 case AFS_4G: 00320 aRes = 4.0/32768.0; 00321 break; 00322 case AFS_8G: 00323 aRes = 8.0/32768.0; 00324 break; 00325 case AFS_16G: 00326 aRes = 16.0/32768.0; 00327 break; 00328 } 00329 } 00330 00331 00332 void readAccelData(int16_t * destination) 00333 { 00334 uint8_t rawData[6]; // x/y/z accel register data stored here 00335 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 00336 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00337 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00338 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00339 } 00340 00341 void readGyroData(int16_t * destination) 00342 { 00343 uint8_t rawData[6]; // x/y/z gyro register data stored here 00344 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 00345 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00346 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00347 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00348 } 00349 00350 void readMagData(int16_t * destination) 00351 { 00352 uint8_t rawData[7]; // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition 00353 if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // wait for magnetometer data ready bit to be set 00354 readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]); // Read the six raw data and ST2 registers sequentially into data array 00355 uint8_t c = rawData[6]; // End data read by reading ST2 register 00356 if(!(c & 0x08)) 00357 { // Check if magnetic sensor overflow set, if not then report data 00358 destination[0] = (int16_t)(((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value 00359 destination[1] = (int16_t)(((int16_t)rawData[3] << 8) | rawData[2]) ; // Data stored as little Endian 00360 destination[2] = (int16_t)(((int16_t)rawData[5] << 8) | rawData[4]) ; 00361 } 00362 } 00363 } 00364 00365 int16_t readTempData() 00366 { 00367 uint8_t rawData[2]; // x/y/z gyro register data stored here 00368 readBytes(MPU9250_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array 00369 return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ; // Turn the MSB and LSB into a 16-bit value 00370 } 00371 00372 00373 void resetMPU9250() 00374 { 00375 // reset device 00376 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 00377 wait(0.1); 00378 } 00379 00380 void initAK8963(float * destination) 00381 { 00382 // First extract the factory calibration for each magnetometer axis 00383 uint8_t rawData[3]; // x/y/z gyro calibration data stored here 00384 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer 00385 wait(0.01); 00386 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode 00387 wait(0.01); 00388 readBytes(AK8963_ADDRESS, AK8963_ASAX, 3, &rawData[0]); // Read the x-, y-, and z-axis calibration values 00389 destination[0] = (float)(rawData[0] - 128)/256.0f + 1.0f; // Return x-axis sensitivity adjustment values, etc. 00390 destination[1] = (float)(rawData[1] - 128)/256.0f + 1.0f; 00391 destination[2] = (float)(rawData[2] - 128)/256.0f + 1.0f; 00392 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer 00393 wait(0.01); 00394 // Configure the magnetometer for continuous read and highest resolution 00395 // set Mscale bit 4 to 1 (0) to enable 16 (14) bit resolution in CNTL register, 00396 // and enable continuous mode data acquisition Mmode (bits [3:0]), 0010 for 8 Hz and 0110 for 100 Hz sample rates 00397 writeByte(AK8963_ADDRESS, AK8963_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR 00398 wait(0.01); 00399 } 00400 00401 00402 void initMPU9250() 00403 { 00404 // Initialize MPU9250 device 00405 // wake up device 00406 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors 00407 wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt 00408 00409 // get stable time source 00410 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 00411 00412 // Configure Gyro and Accelerometer 00413 // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively; 00414 // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both 00415 // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate 00416 writeByte(MPU9250_ADDRESS, CONFIG, 0x03); 00417 00418 // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV) 00419 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above 00420 00421 // Set gyroscope full scale range 00422 // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3 00423 uint8_t c = readByte(MPU9250_ADDRESS, GYRO_CONFIG); 00424 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 00425 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 00426 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro 00427 00428 // Set accelerometer configuration 00429 c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG); 00430 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 00431 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 00432 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer 00433 00434 // Set accelerometer sample rate configuration 00435 // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for 00436 // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz 00437 c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2); 00438 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c & ~0x0F); // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0]) 00439 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c | 0x03); // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz 00440 00441 // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates, 00442 // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting 00443 00444 // Configure Interrupts and Bypass Enable 00445 // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips 00446 // can join the I2C bus and all can be controlled by the Arduino as master 00447 writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22); 00448 writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt 00449 } 00450 00451 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average 00452 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers. 00453 void calibrateMPU9250(float * dest1, float * dest2) 00454 { 00455 uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data 00456 uint16_t ii, packet_count, fifo_count; 00457 int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; 00458 00459 // reset device, reset all registers, clear gyro and accelerometer bias registers 00460 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 00461 wait(0.1); 00462 00463 // get stable time source 00464 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 00465 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); 00466 writeByte(MPU9250_ADDRESS, PWR_MGMT_2, 0x00); 00467 wait(0.2); 00468 00469 // Configure device for bias calculation 00470 writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts 00471 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable FIFO 00472 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source 00473 writeByte(MPU9250_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master 00474 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes 00475 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP 00476 wait(0.015); 00477 00478 // Configure MPU9250 gyro and accelerometer for bias calculation 00479 writeByte(MPU9250_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz 00480 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz 00481 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity 00482 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity 00483 00484 uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec 00485 uint16_t accelsensitivity = 16384; // = 16384 LSB/g 00486 00487 // Configure FIFO to capture accelerometer and gyro data for bias calculation 00488 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x40); // Enable FIFO 00489 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 512 bytes in MPU-9250) 00490 wait(0.04); // accumulate 40 samples in 80 milliseconds = 480 bytes 00491 00492 // At end of sample accumulation, turn off FIFO sensor read 00493 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO 00494 readBytes(MPU9250_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count 00495 fifo_count = ((uint16_t)data[0] << 8) | data[1]; 00496 packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging 00497 00498 for (ii = 0; ii < packet_count; ii++) 00499 { 00500 int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0}; 00501 readBytes(MPU9250_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging 00502 accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO 00503 accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ; 00504 accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ; 00505 gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ; 00506 gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ; 00507 gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ; 00508 00509 accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases 00510 accel_bias[1] += (int32_t) accel_temp[1]; 00511 accel_bias[2] += (int32_t) accel_temp[2]; 00512 gyro_bias[0] += (int32_t) gyro_temp[0]; 00513 gyro_bias[1] += (int32_t) gyro_temp[1]; 00514 gyro_bias[2] += (int32_t) gyro_temp[2]; 00515 } 00516 00517 accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases 00518 accel_bias[1] /= (int32_t) packet_count; 00519 accel_bias[2] /= (int32_t) packet_count; 00520 gyro_bias[0] /= (int32_t) packet_count; 00521 gyro_bias[1] /= (int32_t) packet_count; 00522 gyro_bias[2] /= (int32_t) packet_count; 00523 00524 if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;} // Remove gravity from the z-axis accelerometer bias calculation 00525 else {accel_bias[2] += (int32_t) accelsensitivity;} 00526 00527 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup 00528 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 00529 data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases 00530 data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF; 00531 data[3] = (-gyro_bias[1]/4) & 0xFF; 00532 data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF; 00533 data[5] = (-gyro_bias[2]/4) & 0xFF; 00534 00535 /// Push gyro biases to hardware registers 00536 /* writeByte(MPU9250_ADDRESS, XG_OFFSET_H, data[0]); 00537 writeByte(MPU9250_ADDRESS, XG_OFFSET_L, data[1]); 00538 writeByte(MPU9250_ADDRESS, YG_OFFSET_H, data[2]); 00539 writeByte(MPU9250_ADDRESS, YG_OFFSET_L, data[3]); 00540 writeByte(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]); 00541 writeByte(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]); 00542 */ 00543 dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction 00544 dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity; 00545 dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity; 00546 00547 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain 00548 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold 00549 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature 00550 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that 00551 // the accelerometer biases calculated above must be divided by 8. 00552 00553 int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases 00554 readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values 00555 accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00556 readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]); 00557 accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00558 readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]); 00559 accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00560 00561 uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers 00562 uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis 00563 00564 for(ii = 0; ii < 3; ii++) 00565 { 00566 if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit 00567 } 00568 00569 // Construct total accelerometer bias, including calculated average accelerometer bias from above 00570 accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale) 00571 accel_bias_reg[1] -= (accel_bias[1]/8); 00572 accel_bias_reg[2] -= (accel_bias[2]/8); 00573 00574 data[0] = (accel_bias_reg[0] >> 8) & 0xFF; 00575 data[1] = (accel_bias_reg[0]) & 0xFF; 00576 data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00577 data[2] = (accel_bias_reg[1] >> 8) & 0xFF; 00578 data[3] = (accel_bias_reg[1]) & 0xFF; 00579 data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00580 data[4] = (accel_bias_reg[2] >> 8) & 0xFF; 00581 data[5] = (accel_bias_reg[2]) & 0xFF; 00582 data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00583 00584 // Apparently this is not working for the acceleration biases in the MPU-9250 00585 // Are we handling the temperature correction bit properly? 00586 // Push accelerometer biases to hardware registers 00587 /* writeByte(MPU9250_ADDRESS, XA_OFFSET_H, data[0]); 00588 writeByte(MPU9250_ADDRESS, XA_OFFSET_L, data[1]); 00589 writeByte(MPU9250_ADDRESS, YA_OFFSET_H, data[2]); 00590 writeByte(MPU9250_ADDRESS, YA_OFFSET_L, data[3]); 00591 writeByte(MPU9250_ADDRESS, ZA_OFFSET_H, data[4]); 00592 writeByte(MPU9250_ADDRESS, ZA_OFFSET_L, data[5]); 00593 */ 00594 // Output scaled accelerometer biases for manual subtraction in the main program 00595 dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; 00596 dest2[1] = (float)accel_bias[1]/(float)accelsensitivity; 00597 dest2[2] = (float)accel_bias[2]/(float)accelsensitivity; 00598 } 00599 00600 00601 // Accelerometer and gyroscope self test; check calibration wrt factory settings 00602 void MPU9250SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass 00603 { 00604 uint8_t rawData[6] = {0, 0, 0, 0, 0, 0}; 00605 uint8_t selfTest[6]; 00606 int16_t gAvg[3], aAvg[3], aSTAvg[3], gSTAvg[3]; 00607 float factoryTrim[6]; 00608 uint8_t FS = 0; 00609 00610 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz 00611 writeByte(MPU9250_ADDRESS, CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz 00612 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 1<<FS); // Set full scale range for the gyro to 250 dps 00613 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz 00614 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 1<<FS); // Set full scale range for the accelerometer to 2 g 00615 00616 for( int ii = 0; ii < 200; ii++) { // get average current values of gyro and acclerometer 00617 00618 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 00619 aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00620 aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00621 aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00622 00623 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 00624 gAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00625 gAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00626 gAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00627 } 00628 00629 for (int ii =0; ii < 3; ii++) 00630 { 00631 // Get average of 200 values and store as average current readings 00632 aAvg[ii] /= 200; 00633 gAvg[ii] /= 200; 00634 } 00635 00636 // Configure the accelerometer for self-test 00637 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g 00638 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s 00639 //delay(25); // Delay a while to let the device stabilize 00640 00641 for( int ii = 0; ii < 200; ii++) 00642 { 00643 // get average self-test values of gyro and acclerometer 00644 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 00645 aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00646 aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00647 aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00648 00649 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 00650 gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00651 gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00652 gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00653 } 00654 00655 for (int ii =0; ii < 3; ii++) 00656 { 00657 // 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 //delay(25); // 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 { 00687 destination[i] = 100.0*((float)(aSTAvg[i] - aAvg[i]))/factoryTrim[i]; // Report percent differences 00688 destination[i+3] = 100.0*((float)(gSTAvg[i] - gAvg[i]))/factoryTrim[i+3]; // Report percent differences 00689 } 00690 00691 } 00692 00693 void MadgwickFilterUpdate_6axis(float ax, float ay, float az, float wx, float wy, float wz) 00694 { 00695 // Local system variables 00696 float norm; // vector norm 00697 float SEqDot_omega_1, SEqDot_omega_2, SEqDot_omega_3, SEqDot_omega_4; // quaternion derrivative from gyroscopes elements 00698 float f_1, f_2, f_3; // objective function elements 00699 float J_11or24, J_12or23, J_13or22, J_14or21, J_32, J_33; // objective function Jacobian elements 00700 float SEqHatDot_1, SEqHatDot_2, SEqHatDot_3, SEqHatDot_4; // estimated direction of the gyroscope error 00701 00702 // Axulirary variables to avoid reapeated calcualtions 00703 float halfSEq_1 = 0.5f * q1; 00704 float halfSEq_2 = 0.5f * q2; 00705 float halfSEq_3 = 0.5f * q3; 00706 float halfSEq_4 = 0.5f * q4; 00707 float twoSEq_1 = 2.0f * q1; 00708 float twoSEq_2 = 2.0f * q2; 00709 float twoSEq_3 = 2.0f * q3; 00710 00711 // Normalise the accelerometer measurement 00712 norm = sqrt(ax * ax + ay * ay + az * az); 00713 ax /= norm; 00714 ay /= norm; 00715 az /= norm; 00716 00717 // Compute the objective function and Jacobian 00718 f_1 = twoSEq_2 * q4 - twoSEq_1 * q3 - ax; 00719 f_2 = twoSEq_1 * q2 + twoSEq_3 * q4 - ay; 00720 f_3 = 1.0f - twoSEq_2 * q2 - twoSEq_3 * q3 - az; 00721 J_11or24 = twoSEq_3; // J_11 negated in matrix multiplication 00722 J_12or23 = 2.0f * q4; 00723 J_13or22 = twoSEq_1; // J_12 negated in matrix multiplication 00724 J_14or21 = twoSEq_2; 00725 J_32 = 2.0f * J_14or21; // negated in matrix multiplication 00726 J_33 = 2.0f * J_11or24; // negated in matrix multiplication 00727 00728 // Compute the gradient (matrix multiplication) 00729 SEqHatDot_1 = J_14or21 * f_2 - J_11or24 * f_1; 00730 SEqHatDot_2 = J_12or23 * f_1 + J_13or22 * f_2 - J_32 * f_3; 00731 SEqHatDot_3 = J_12or23 * f_2 - J_33 * f_3 - J_13or22 * f_1; 00732 SEqHatDot_4 = J_14or21 * f_1 + J_11or24 * f_2; 00733 00734 // Normalise the gradient 00735 norm = sqrt(SEqHatDot_1 * SEqHatDot_1 + SEqHatDot_2 * SEqHatDot_2 + SEqHatDot_3 * SEqHatDot_3 + SEqHatDot_4 * SEqHatDot_4); 00736 SEqHatDot_1 /= norm; 00737 SEqHatDot_2 /= norm; 00738 SEqHatDot_3 /= norm; 00739 SEqHatDot_4 /= norm; 00740 00741 // Compute the quaternion derrivative measured by gyroscopes 00742 SEqDot_omega_1 = -halfSEq_2 * wx - halfSEq_3 * wy - halfSEq_4 * wz; 00743 SEqDot_omega_2 = halfSEq_1 * wx + halfSEq_3 * wz - halfSEq_4 * wy; 00744 SEqDot_omega_3 = halfSEq_1 * wy - halfSEq_2 * wz + halfSEq_4 * wx; 00745 SEqDot_omega_4 = halfSEq_1 * wz + halfSEq_2 * wy - halfSEq_3 * wx; 00746 00747 // Compute then integrate the estimated quaternion derrivative 00748 q1 += (SEqDot_omega_1 - (beta * SEqHatDot_1)) * delt_t; 00749 q2 += (SEqDot_omega_2 - (beta * SEqHatDot_2)) * delt_t; 00750 q3 += (SEqDot_omega_3 - (beta * SEqHatDot_3)) * delt_t; 00751 q4 += (SEqDot_omega_4 - (beta * SEqHatDot_4)) * delt_t; 00752 00753 // Normalise quaternion 00754 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); 00755 q1 /= norm; 00756 q2 /= norm; 00757 q3 /= norm; 00758 q4 /= norm; 00759 00760 } 00761 00762 00763 00764 // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and 00765 // measured ones. 00766 /* 00767 void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) 00768 { 00769 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability 00770 float norm; 00771 float hx, hy, bx, bz; 00772 float vx, vy, vz, wx, wy, wz; 00773 float ex, ey, ez; 00774 float pa, pb, pc; 00775 00776 // Auxiliary variables to avoid repeated arithmetic 00777 float q1q1 = q1 * q1; 00778 float q1q2 = q1 * q2; 00779 float q1q3 = q1 * q3; 00780 float q1q4 = q1 * q4; 00781 float q2q2 = q2 * q2; 00782 float q2q3 = q2 * q3; 00783 float q2q4 = q2 * q4; 00784 float q3q3 = q3 * q3; 00785 float q3q4 = q3 * q4; 00786 float q4q4 = q4 * q4; 00787 00788 // Normalise accelerometer measurement 00789 norm = sqrt(ax * ax + ay * ay + az * az); 00790 if (norm == 0.0f) return; // handle NaN 00791 norm = 1.0f / norm; // use reciprocal for division 00792 ax *= norm; 00793 ay *= norm; 00794 az *= norm; 00795 00796 // Normalise magnetometer measurement 00797 norm = sqrt(mx * mx + my * my + mz * mz); 00798 if (norm == 0.0f) return; // handle NaN 00799 norm = 1.0f / norm; // use reciprocal for division 00800 mx *= norm; 00801 my *= norm; 00802 mz *= norm; 00803 00804 // Reference direction of Earth's magnetic field 00805 hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3); 00806 hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2); 00807 bx = sqrt((hx * hx) + (hy * hy)); 00808 bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3); 00809 00810 // Estimated direction of gravity and magnetic field 00811 vx = 2.0f * (q2q4 - q1q3); 00812 vy = 2.0f * (q1q2 + q3q4); 00813 vz = q1q1 - q2q2 - q3q3 + q4q4; 00814 wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3); 00815 wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4); 00816 wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3); 00817 00818 // Error is cross product between estimated direction and measured direction of gravity 00819 ex = (ay * vz - az * vy) + (my * wz - mz * wy); 00820 ey = (az * vx - ax * vz) + (mz * wx - mx * wz); 00821 ez = (ax * vy - ay * vx) + (mx * wy - my * wx); 00822 if (Ki > 0.0f) 00823 { 00824 eInt[0] += ex; // accumulate integral error 00825 eInt[1] += ey; 00826 eInt[2] += ez; 00827 } 00828 else 00829 { 00830 eInt[0] = 0.0f; // prevent integral wind up 00831 eInt[1] = 0.0f; 00832 eInt[2] = 0.0f; 00833 } 00834 00835 // Apply feedback terms 00836 gx = gx + Kp * ex + Ki * eInt[0]; 00837 gy = gy + Kp * ey + Ki * eInt[1]; 00838 gz = gz + Kp * ez + Ki * eInt[2]; 00839 00840 // Integrate rate of change of quaternion 00841 pa = q2; 00842 pb = q3; 00843 pc = q4; 00844 q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * delt_t); 00845 q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * delt_t); 00846 q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * delt_t); 00847 q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * delt_t); 00848 00849 // Normalise quaternion 00850 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); 00851 norm = 1.0f / norm; 00852 q[0] = q1 * norm; 00853 q[1] = q2 * norm; 00854 q[2] = q3 * norm; 00855 q[3] = q4 * norm; 00856 00857 } 00858 */ 00859 }; 00860 #endif
Generated on Mon Jul 25 2022 06:11:32 by
1.7.2