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