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