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 00216 // parameters for 6 DoF sensor fusion calculations 00217 float PI = 3.14159265358979323846f; 00218 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 00219 float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta 00220 float GyroMeasDrift = PI * (1.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) 00221 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 00222 #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 00223 #define Ki 0.0f 00224 00225 float pitch, yaw, roll; 00226 float deltat = 0.0f; // integration interval for both filter schemes 00227 float lastUpdate = 0.0f, firstUpdate = 0.0f, Now = 0.0f; // used to calculate integration interval // used to calculate integration interval 00228 float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion 00229 float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method 00230 00231 class MPU9250 { 00232 00233 protected: 00234 00235 public: 00236 //=================================================================================================================== 00237 //====== Set of useful function to access acceleratio, gyroscope, and temperature data 00238 //=================================================================================================================== 00239 00240 void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) 00241 { 00242 char data_write[2]; 00243 data_write[0] = subAddress; 00244 data_write[1] = data; 00245 i2c.write(address, data_write, 2, 0); 00246 } 00247 00248 char readByte(uint8_t address, uint8_t subAddress) 00249 { 00250 char data[1]; // `data` will store the register data 00251 char data_write[1]; 00252 data_write[0] = subAddress; 00253 i2c.write(address, data_write, 1, 1); // no stop 00254 i2c.read(address, data, 1, 0); 00255 return data[0]; 00256 } 00257 00258 void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) 00259 { 00260 char data[14]; 00261 char data_write[1]; 00262 data_write[0] = subAddress; 00263 i2c.write(address, data_write, 1, 1); // no stop 00264 i2c.read(address, data, count, 0); 00265 for(int ii = 0; ii < count; ii++) { 00266 dest[ii] = data[ii]; 00267 } 00268 } 00269 00270 void getMres() { 00271 switch (Mscale) 00272 { 00273 // Possible magnetometer scales (and their register bit settings) are: 00274 // 14 bit resolution (0) and 16 bit resolution (1) 00275 case MFS_14BITS: 00276 mRes = 10.0*4219.0/8190.0; // Proper scale to return milliGauss 00277 break; 00278 case MFS_16BITS: 00279 mRes = 10.0*4219.0/32760.0; // Proper scale to return milliGauss 00280 break; 00281 } 00282 } 00283 00284 void getGres() { 00285 switch (Gscale) 00286 { 00287 // Possible gyro scales (and their register bit settings) are: 00288 // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11). 00289 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 00290 case GFS_250DPS: 00291 gRes = 250.0/32768.0; 00292 break; 00293 case GFS_500DPS: 00294 gRes = 500.0/32768.0; 00295 break; 00296 case GFS_1000DPS: 00297 gRes = 1000.0/32768.0; 00298 break; 00299 case GFS_2000DPS: 00300 gRes = 2000.0/32768.0; 00301 break; 00302 } 00303 } 00304 00305 void getAres() { 00306 switch (Ascale) 00307 { 00308 // Possible accelerometer scales (and their register bit settings) are: 00309 // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11). 00310 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 00311 case AFS_2G: 00312 aRes = 2.0/32768.0; 00313 break; 00314 case AFS_4G: 00315 aRes = 4.0/32768.0; 00316 break; 00317 case AFS_8G: 00318 aRes = 8.0/32768.0; 00319 break; 00320 case AFS_16G: 00321 aRes = 16.0/32768.0; 00322 break; 00323 } 00324 } 00325 00326 00327 void readAccelData(int16_t * destination) 00328 { 00329 uint8_t rawData[6]; // x/y/z accel register data stored here 00330 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 00331 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00332 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00333 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00334 } 00335 00336 void readGyroData(int16_t * destination) 00337 { 00338 uint8_t rawData[6]; // x/y/z gyro register data stored here 00339 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 00340 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00341 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00342 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00343 } 00344 00345 void readMagData(int16_t * destination) 00346 { 00347 uint8_t rawData[7]; // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition 00348 if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // wait for magnetometer data ready bit to be set 00349 readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]); // Read the six raw data and ST2 registers sequentially into data array 00350 uint8_t c = rawData[6]; // End data read by reading ST2 register 00351 if(!(c & 0x08)) 00352 { // Check if magnetic sensor overflow set, if not then report data 00353 destination[0] = (int16_t)(((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value 00354 destination[1] = (int16_t)(((int16_t)rawData[3] << 8) | rawData[2]) ; // Data stored as little Endian 00355 destination[2] = (int16_t)(((int16_t)rawData[5] << 8) | rawData[4]) ; 00356 } 00357 } 00358 } 00359 00360 int16_t readTempData() 00361 { 00362 uint8_t rawData[2]; // x/y/z gyro register data stored here 00363 readBytes(MPU9250_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array 00364 return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ; // Turn the MSB and LSB into a 16-bit value 00365 } 00366 00367 00368 void resetMPU9250() 00369 { 00370 // reset device 00371 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 00372 wait(0.1); 00373 } 00374 00375 void initAK8963(float * destination) 00376 { 00377 // First extract the factory calibration for each magnetometer axis 00378 uint8_t rawData[3]; // x/y/z gyro calibration data stored here 00379 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer 00380 wait(0.01); 00381 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode 00382 wait(0.01); 00383 readBytes(AK8963_ADDRESS, AK8963_ASAX, 3, &rawData[0]); // Read the x-, y-, and z-axis calibration values 00384 destination[0] = (float)(rawData[0] - 128)/256.0f + 1.0f; // Return x-axis sensitivity adjustment values, etc. 00385 destination[1] = (float)(rawData[1] - 128)/256.0f + 1.0f; 00386 destination[2] = (float)(rawData[2] - 128)/256.0f + 1.0f; 00387 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer 00388 wait(0.01); 00389 // Configure the magnetometer for continuous read and highest resolution 00390 // set Mscale bit 4 to 1 (0) to enable 16 (14) bit resolution in CNTL register, 00391 // and enable continuous mode data acquisition Mmode (bits [3:0]), 0010 for 8 Hz and 0110 for 100 Hz sample rates 00392 writeByte(AK8963_ADDRESS, AK8963_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR 00393 wait(0.01); 00394 } 00395 00396 00397 void initMPU9250() 00398 { 00399 // Initialize MPU9250 device 00400 // wake up device 00401 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors 00402 wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt 00403 00404 // get stable time source 00405 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 00406 00407 // Configure Gyro and Accelerometer 00408 // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively; 00409 // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both 00410 // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate 00411 writeByte(MPU9250_ADDRESS, CONFIG, 0x03); 00412 00413 // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV) 00414 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above 00415 00416 // Set gyroscope full scale range 00417 // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3 00418 uint8_t c = readByte(MPU9250_ADDRESS, GYRO_CONFIG); 00419 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 00420 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 00421 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro 00422 00423 // Set accelerometer configuration 00424 c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG); 00425 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 00426 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 00427 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer 00428 00429 // Set accelerometer sample rate configuration 00430 // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for 00431 // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz 00432 c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2); 00433 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c & ~0x0F); // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0]) 00434 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c | 0x03); // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz 00435 00436 // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates, 00437 // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting 00438 00439 // Configure Interrupts and Bypass Enable 00440 // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips 00441 // can join the I2C bus and all can be controlled by the Arduino as master 00442 writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22); 00443 writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt 00444 } 00445 00446 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average 00447 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers. 00448 void calibrateMPU9250(float * dest1, float * dest2) 00449 { 00450 uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data 00451 uint16_t ii, packet_count, fifo_count; 00452 int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; 00453 00454 // reset device, reset all registers, clear gyro and accelerometer bias registers 00455 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 00456 wait(0.1); 00457 00458 // get stable time source 00459 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 00460 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); 00461 writeByte(MPU9250_ADDRESS, PWR_MGMT_2, 0x00); 00462 wait(0.2); 00463 00464 // Configure device for bias calculation 00465 writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts 00466 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable FIFO 00467 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source 00468 writeByte(MPU9250_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master 00469 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes 00470 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP 00471 wait(0.015); 00472 00473 // Configure MPU9250 gyro and accelerometer for bias calculation 00474 writeByte(MPU9250_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz 00475 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz 00476 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity 00477 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity 00478 00479 uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec 00480 uint16_t accelsensitivity = 16384; // = 16384 LSB/g 00481 00482 // Configure FIFO to capture accelerometer and gyro data for bias calculation 00483 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x40); // Enable FIFO 00484 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 512 bytes in MPU-9250) 00485 wait(0.04); // accumulate 40 samples in 80 milliseconds = 480 bytes 00486 00487 // At end of sample accumulation, turn off FIFO sensor read 00488 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO 00489 readBytes(MPU9250_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count 00490 fifo_count = ((uint16_t)data[0] << 8) | data[1]; 00491 packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging 00492 00493 for (ii = 0; ii < packet_count; ii++) 00494 { 00495 int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0}; 00496 readBytes(MPU9250_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging 00497 accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO 00498 accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ; 00499 accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ; 00500 gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ; 00501 gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ; 00502 gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ; 00503 00504 accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases 00505 accel_bias[1] += (int32_t) accel_temp[1]; 00506 accel_bias[2] += (int32_t) accel_temp[2]; 00507 gyro_bias[0] += (int32_t) gyro_temp[0]; 00508 gyro_bias[1] += (int32_t) gyro_temp[1]; 00509 gyro_bias[2] += (int32_t) gyro_temp[2]; 00510 } 00511 00512 accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases 00513 accel_bias[1] /= (int32_t) packet_count; 00514 accel_bias[2] /= (int32_t) packet_count; 00515 gyro_bias[0] /= (int32_t) packet_count; 00516 gyro_bias[1] /= (int32_t) packet_count; 00517 gyro_bias[2] /= (int32_t) packet_count; 00518 00519 if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;} // Remove gravity from the z-axis accelerometer bias calculation 00520 else {accel_bias[2] += (int32_t) accelsensitivity;} 00521 00522 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup 00523 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 00524 data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases 00525 data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF; 00526 data[3] = (-gyro_bias[1]/4) & 0xFF; 00527 data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF; 00528 data[5] = (-gyro_bias[2]/4) & 0xFF; 00529 00530 /// Push gyro biases to hardware registers 00531 /* writeByte(MPU9250_ADDRESS, XG_OFFSET_H, data[0]); 00532 writeByte(MPU9250_ADDRESS, XG_OFFSET_L, data[1]); 00533 writeByte(MPU9250_ADDRESS, YG_OFFSET_H, data[2]); 00534 writeByte(MPU9250_ADDRESS, YG_OFFSET_L, data[3]); 00535 writeByte(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]); 00536 writeByte(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]); 00537 */ 00538 dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction 00539 dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity; 00540 dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity; 00541 00542 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain 00543 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold 00544 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature 00545 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that 00546 // the accelerometer biases calculated above must be divided by 8. 00547 00548 int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases 00549 readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values 00550 accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00551 readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]); 00552 accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00553 readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]); 00554 accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00555 00556 uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers 00557 uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis 00558 00559 for(ii = 0; ii < 3; ii++) { 00560 if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit 00561 } 00562 00563 // Construct total accelerometer bias, including calculated average accelerometer bias from above 00564 accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale) 00565 accel_bias_reg[1] -= (accel_bias[1]/8); 00566 accel_bias_reg[2] -= (accel_bias[2]/8); 00567 00568 data[0] = (accel_bias_reg[0] >> 8) & 0xFF; 00569 data[1] = (accel_bias_reg[0]) & 0xFF; 00570 data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00571 data[2] = (accel_bias_reg[1] >> 8) & 0xFF; 00572 data[3] = (accel_bias_reg[1]) & 0xFF; 00573 data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00574 data[4] = (accel_bias_reg[2] >> 8) & 0xFF; 00575 data[5] = (accel_bias_reg[2]) & 0xFF; 00576 data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00577 00578 // Apparently this is not working for the acceleration biases in the MPU-9250 00579 // Are we handling the temperature correction bit properly? 00580 // Push accelerometer biases to hardware registers 00581 /* writeByte(MPU9250_ADDRESS, XA_OFFSET_H, data[0]); 00582 writeByte(MPU9250_ADDRESS, XA_OFFSET_L, data[1]); 00583 writeByte(MPU9250_ADDRESS, YA_OFFSET_H, data[2]); 00584 writeByte(MPU9250_ADDRESS, YA_OFFSET_L, data[3]); 00585 writeByte(MPU9250_ADDRESS, ZA_OFFSET_H, data[4]); 00586 writeByte(MPU9250_ADDRESS, ZA_OFFSET_L, data[5]); 00587 */ 00588 // Output scaled accelerometer biases for manual subtraction in the main program 00589 dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; 00590 dest2[1] = (float)accel_bias[1]/(float)accelsensitivity; 00591 dest2[2] = (float)accel_bias[2]/(float)accelsensitivity; 00592 } 00593 00594 00595 // Accelerometer and gyroscope self test; check calibration wrt factory settings 00596 void MPU9250SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass 00597 { 00598 uint8_t rawData[6] = {0, 0, 0, 0, 0, 0}; 00599 uint8_t selfTest[6]; 00600 int16_t gAvg[3], aAvg[3], aSTAvg[3], gSTAvg[3]; 00601 float factoryTrim[6]; 00602 uint8_t FS = 0; 00603 00604 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz 00605 writeByte(MPU9250_ADDRESS, CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz 00606 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 1<<FS); // Set full scale range for the gyro to 250 dps 00607 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz 00608 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 1<<FS); // Set full scale range for the accelerometer to 2 g 00609 00610 for( int ii = 0; ii < 200; ii++) { // get average current values of gyro and acclerometer 00611 00612 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 00613 aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00614 aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00615 aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00616 00617 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 00618 gAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00619 gAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00620 gAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00621 } 00622 00623 for (int ii =0; ii < 3; ii++) 00624 { 00625 // Get average of 200 values and store as average current readings 00626 aAvg[ii] /= 200; 00627 gAvg[ii] /= 200; 00628 } 00629 00630 // Configure the accelerometer for self-test 00631 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g 00632 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s 00633 //delay(25); // Delay a while to let the device stabilize 00634 00635 for( int ii = 0; ii < 200; ii++) 00636 { 00637 // get average self-test values of gyro and acclerometer 00638 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 00639 aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00640 aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00641 aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00642 00643 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 00644 gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00645 gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00646 gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00647 } 00648 00649 for (int ii =0; ii < 3; ii++) 00650 { 00651 // Get average of 200 values and store as average self-test readings 00652 aSTAvg[ii] /= 200; 00653 gSTAvg[ii] /= 200; 00654 } 00655 00656 // Configure the gyro and accelerometer for normal operation 00657 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); 00658 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); 00659 //delay(25); // Delay a while to let the device stabilize 00660 00661 // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg 00662 selfTest[0] = readByte(MPU9250_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results 00663 selfTest[1] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_ACCEL); // Y-axis accel self-test results 00664 selfTest[2] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_ACCEL); // Z-axis accel self-test results 00665 selfTest[3] = readByte(MPU9250_ADDRESS, SELF_TEST_X_GYRO); // X-axis gyro self-test results 00666 selfTest[4] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_GYRO); // Y-axis gyro self-test results 00667 selfTest[5] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_GYRO); // Z-axis gyro self-test results 00668 00669 // Retrieve factory self-test value from self-test code reads 00670 factoryTrim[0] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[0] - 1.0) )); // FT[Xa] factory trim calculation 00671 factoryTrim[1] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[1] - 1.0) )); // FT[Ya] factory trim calculation 00672 factoryTrim[2] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[2] - 1.0) )); // FT[Za] factory trim calculation 00673 factoryTrim[3] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[3] - 1.0) )); // FT[Xg] factory trim calculation 00674 factoryTrim[4] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[4] - 1.0) )); // FT[Yg] factory trim calculation 00675 factoryTrim[5] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[5] - 1.0) )); // FT[Zg] factory trim calculation 00676 00677 // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response 00678 // To get percent, must multiply by 100 00679 for (int i = 0; i < 3; i++) 00680 { 00681 destination[i] = 100.0*((float)(aSTAvg[i] - aAvg[i]))/factoryTrim[i]; // Report percent differences 00682 destination[i+3] = 100.0*((float)(gSTAvg[i] - gAvg[i]))/factoryTrim[i+3]; // Report percent differences 00683 } 00684 00685 } 00686 00687 00688 00689 // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" 00690 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details) 00691 // which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute 00692 // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc. 00693 // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms 00694 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz! 00695 void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) 00696 { 00697 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability 00698 float norm; 00699 float hx, hy, _2bx, _2bz; 00700 float s1, s2, s3, s4; 00701 float qDot1, qDot2, qDot3, qDot4; 00702 00703 // Auxiliary variables to avoid repeated arithmetic 00704 float _2q1mx; 00705 float _2q1my; 00706 float _2q1mz; 00707 float _2q2mx; 00708 float _4bx; 00709 float _4bz; 00710 float _2q1 = 2.0f * q1; 00711 float _2q2 = 2.0f * q2; 00712 float _2q3 = 2.0f * q3; 00713 float _2q4 = 2.0f * q4; 00714 float _2q1q3 = 2.0f * q1 * q3; 00715 float _2q3q4 = 2.0f * q3 * q4; 00716 float q1q1 = q1 * q1; 00717 float q1q2 = q1 * q2; 00718 float q1q3 = q1 * q3; 00719 float q1q4 = q1 * q4; 00720 float q2q2 = q2 * q2; 00721 float q2q3 = q2 * q3; 00722 float q2q4 = q2 * q4; 00723 float q3q3 = q3 * q3; 00724 float q3q4 = q3 * q4; 00725 float q4q4 = q4 * q4; 00726 00727 // Normalise accelerometer measurement 00728 norm = sqrt(ax * ax + ay * ay + az * az); 00729 if (norm == 0.0f) return; // handle NaN 00730 norm = 1.0f/norm; 00731 ax *= norm; 00732 ay *= norm; 00733 az *= norm; 00734 00735 // Normalise magnetometer measurement 00736 norm = sqrt(mx * mx + my * my + mz * mz); 00737 if (norm == 0.0f) return; // handle NaN 00738 norm = 1.0f/norm; 00739 mx *= norm; 00740 my *= norm; 00741 mz *= norm; 00742 00743 // Reference direction of Earth's magnetic field 00744 _2q1mx = 2.0f * q1 * mx; 00745 _2q1my = 2.0f * q1 * my; 00746 _2q1mz = 2.0f * q1 * mz; 00747 _2q2mx = 2.0f * q2 * mx; 00748 hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4; 00749 hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4; 00750 _2bx = sqrt(hx * hx + hy * hy); 00751 _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4; 00752 _4bx = 2.0f * _2bx; 00753 _4bz = 2.0f * _2bz; 00754 00755 // Gradient decent algorithm corrective step 00756 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); 00757 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); 00758 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); 00759 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); 00760 norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude 00761 norm = 1.0f/norm; 00762 s1 *= norm; 00763 s2 *= norm; 00764 s3 *= norm; 00765 s4 *= norm; 00766 00767 // Compute rate of change of quaternion 00768 qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1; 00769 qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2; 00770 qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3; 00771 qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4; 00772 00773 // Integrate to yield quaternion 00774 q1 += qDot1 * deltat; 00775 q2 += qDot2 * deltat; 00776 q3 += qDot3 * deltat; 00777 q4 += qDot4 * deltat; 00778 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion 00779 norm = 1.0f/norm; 00780 q[0] = q1 * norm; 00781 q[1] = q2 * norm; 00782 q[2] = q3 * norm; 00783 q[3] = q4 * norm; 00784 00785 } 00786 00787 00788 00789 // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and 00790 // measured ones. 00791 void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) 00792 { 00793 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability 00794 float norm; 00795 float hx, hy, bx, bz; 00796 float vx, vy, vz, wx, wy, wz; 00797 float ex, ey, ez; 00798 float pa, pb, pc; 00799 00800 // Auxiliary variables to avoid repeated arithmetic 00801 float q1q1 = q1 * q1; 00802 float q1q2 = q1 * q2; 00803 float q1q3 = q1 * q3; 00804 float q1q4 = q1 * q4; 00805 float q2q2 = q2 * q2; 00806 float q2q3 = q2 * q3; 00807 float q2q4 = q2 * q4; 00808 float q3q3 = q3 * q3; 00809 float q3q4 = q3 * q4; 00810 float q4q4 = q4 * q4; 00811 00812 // Normalise accelerometer measurement 00813 norm = sqrt(ax * ax + ay * ay + az * az); 00814 if (norm == 0.0f) return; // handle NaN 00815 norm = 1.0f / norm; // use reciprocal for division 00816 ax *= norm; 00817 ay *= norm; 00818 az *= norm; 00819 00820 // Normalise magnetometer measurement 00821 norm = sqrt(mx * mx + my * my + mz * mz); 00822 if (norm == 0.0f) return; // handle NaN 00823 norm = 1.0f / norm; // use reciprocal for division 00824 mx *= norm; 00825 my *= norm; 00826 mz *= norm; 00827 00828 // Reference direction of Earth's magnetic field 00829 hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3); 00830 hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2); 00831 bx = sqrt((hx * hx) + (hy * hy)); 00832 bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3); 00833 00834 // Estimated direction of gravity and magnetic field 00835 vx = 2.0f * (q2q4 - q1q3); 00836 vy = 2.0f * (q1q2 + q3q4); 00837 vz = q1q1 - q2q2 - q3q3 + q4q4; 00838 wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3); 00839 wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4); 00840 wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3); 00841 00842 // Error is cross product between estimated direction and measured direction of gravity 00843 ex = (ay * vz - az * vy) + (my * wz - mz * wy); 00844 ey = (az * vx - ax * vz) + (mz * wx - mx * wz); 00845 ez = (ax * vy - ay * vx) + (mx * wy - my * wx); 00846 if (Ki > 0.0f) 00847 { 00848 eInt[0] += ex; // accumulate integral error 00849 eInt[1] += ey; 00850 eInt[2] += ez; 00851 } 00852 else 00853 { 00854 eInt[0] = 0.0f; // prevent integral wind up 00855 eInt[1] = 0.0f; 00856 eInt[2] = 0.0f; 00857 } 00858 00859 // Apply feedback terms 00860 gx = gx + Kp * ex + Ki * eInt[0]; 00861 gy = gy + Kp * ey + Ki * eInt[1]; 00862 gz = gz + Kp * ez + Ki * eInt[2]; 00863 00864 // Integrate rate of change of quaternion 00865 pa = q2; 00866 pb = q3; 00867 pc = q4; 00868 q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat); 00869 q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat); 00870 q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat); 00871 q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat); 00872 00873 // Normalise quaternion 00874 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); 00875 norm = 1.0f / norm; 00876 q[0] = q1 * norm; 00877 q[1] = q2 * norm; 00878 q[2] = q3 * norm; 00879 q[3] = q4 * norm; 00880 00881 } 00882 }; 00883 #endif
Generated on Mon Jul 25 2022 05:56:37 by
1.7.2