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