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