Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
MPU9250.cpp
00001 #include "mbed.h" 00002 #include "math.h" 00003 #include "MPU9250.h" 00004 00005 00006 MPU9250::MPU9250(PinName sda, PinName scl, RawSerial* serial_p) 00007 : 00008 i2c_p(new I2C(sda,scl)), 00009 i2c(*i2c_p), 00010 pc_p(serial_p) 00011 { 00012 initializeValue(); 00013 } 00014 00015 MPU9250::~MPU9250(){} 00016 00017 00018 /*---------- public function ----------*/ 00019 bool MPU9250::Initialize(void){ 00020 uint8_t whoami; 00021 00022 i2c.frequency(400000); // use fast (400 kHz) I2C 00023 timer.start(); 00024 00025 whoami = Whoami_MPU9250(); 00026 pc_p->printf("I AM 0x%x\n\r", whoami); pc_p->printf("I SHOULD BE 0x71\n\r"); 00027 00028 if(whoami == IAM_MPU9250){ 00029 resetMPU9250(); // Reset registers to default in preparation for device calibration 00030 calibrateMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers 00031 wait(1); 00032 00033 initMPU9250(); 00034 initAK8963(magCalibration); 00035 00036 pc_p->printf("Accelerometer full-scale range = %f g\n\r", 2.0f*(float)(1<<Ascale)); 00037 pc_p->printf("Gyroscope full-scale range = %f deg/s\n\r", 250.0f*(float)(1<<Gscale)); 00038 00039 if(Mscale == 0) pc_p->printf("Magnetometer resolution = 14 bits\n\r"); 00040 if(Mscale == 1) pc_p->printf("Magnetometer resolution = 16 bits\n\r"); 00041 if(Mmode == 2) pc_p->printf("Magnetometer ODR = 8 Hz\n\r"); 00042 if(Mmode == 6) pc_p->printf("Magnetometer ODR = 100 Hz\n\r"); 00043 00044 getAres(); 00045 getGres(); 00046 getMres(); 00047 00048 pc_p->printf("mpu9250 initialized\r\n"); 00049 return true; 00050 }else return false; 00051 } 00052 00053 bool MPU9250::sensingAcGyMg(){ 00054 if(readByte(MPU9250_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt 00055 sensingAccel(); 00056 sensingGyro(); 00057 sensingMag(); 00058 return true; 00059 }else return false; 00060 } 00061 00062 00063 void MPU9250::calculatePostureAngle(float degree[3]){ 00064 Now = timer.read_us(); 00065 deltat = (float)((Now - lastUpdate)/1000000.0f); // set integration time by time elapsed since last filter update 00066 lastUpdate = Now; 00067 00068 // if(lastUpdate - firstUpdate > 10000000.0f) { 00069 // beta = 0.04; // decrease filter gain after stabilized 00070 // zeta = 0.015; // increasey bias drift gain after stabilized 00071 // } 00072 00073 // Pass gyro rate as rad/s 00074 MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); 00075 MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); //my, mx, mzになってるけどセンサの設置上の都合だろうか 00076 00077 // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. 00078 // In this coordinate system, the positive z-axis is down toward Earth. 00079 // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. 00080 // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. 00081 // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. 00082 // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. 00083 // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be 00084 // applied in the correct order which for this configuration is yaw, pitch, and then roll. 00085 // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. 00086 translateQuaternionToDeg(q); 00087 calibrateDegree(); 00088 degree[0] = roll; 00089 degree[1] = pitch; 00090 degree[2] = yaw; 00091 } 00092 00093 00094 float MPU9250::calculateYawByMg(){ 00095 transformCoordinateFromCompassToMPU(); 00096 lpmag[0] = LPGAIN_MAG *lpmag[0] + (1 - LPGAIN_MAG)*mx; 00097 lpmag[1] = LPGAIN_MAG *lpmag[1] + (1 - LPGAIN_MAG)*my; 00098 lpmag[2] = LPGAIN_MAG *lpmag[2] + (1 - LPGAIN_MAG)*mz; 00099 00100 float radroll = PI/180.0f * roll; 00101 float radpitch = PI/180.0f * pitch; 00102 00103 return 180.0f/PI * atan2(lpmag[2]*sin(radpitch) - lpmag[1]*cos(radpitch), 00104 lpmag[0]*cos(radroll) - lpmag[1]*sin(radroll)*sin(radpitch) + lpmag[2]*sin(radroll)*cos(radpitch)); 00105 } 00106 00107 00108 // Accelerometer and gyroscope self test; check calibration wrt factory settings 00109 void MPU9250::MPU9250SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass 00110 { 00111 uint8_t rawData[6] = {0, 0, 0, 0, 0, 0}; 00112 uint8_t selfTest[6]; 00113 int16_t gAvg[3], aAvg[3], aSTAvg[3], gSTAvg[3]; 00114 float factoryTrim[6]; 00115 uint8_t FS = 0; 00116 00117 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz 00118 writeByte(MPU9250_ADDRESS, CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz 00119 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 1<<FS); // Set full scale range for the gyro to 250 dps 00120 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz 00121 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 1<<FS); // Set full scale range for the accelerometer to 2 g 00122 00123 for( int ii = 0; ii < 200; ii++) { // get average current values of gyro and acclerometer 00124 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 00125 aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00126 aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00127 aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00128 00129 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 00130 gAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00131 gAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00132 gAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00133 } 00134 00135 for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average current readings 00136 aAvg[ii] /= 200; 00137 gAvg[ii] /= 200; 00138 } 00139 00140 // Configure the accelerometer for self-test 00141 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g 00142 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s 00143 //delay(55); // Delay a while to let the device stabilize 00144 00145 for( int ii = 0; ii < 200; ii++) { // get average self-test values of gyro and acclerometer 00146 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 00147 aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00148 aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00149 aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00150 00151 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 00152 gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00153 gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00154 gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00155 } 00156 00157 for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average self-test readings 00158 aSTAvg[ii] /= 200; 00159 gSTAvg[ii] /= 200; 00160 } 00161 00162 // Configure the gyro and accelerometer for normal operation 00163 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); 00164 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); 00165 //delay(45); // Delay a while to let the device stabilize 00166 00167 // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg 00168 selfTest[0] = readByte(MPU9250_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results 00169 selfTest[1] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_ACCEL); // Y-axis accel self-test results 00170 selfTest[2] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_ACCEL); // Z-axis accel self-test results 00171 selfTest[3] = readByte(MPU9250_ADDRESS, SELF_TEST_X_GYRO); // X-axis gyro self-test results 00172 selfTest[4] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_GYRO); // Y-axis gyro self-test results 00173 selfTest[5] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_GYRO); // Z-axis gyro self-test results 00174 00175 // Retrieve factory self-test value from self-test code reads 00176 factoryTrim[0] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[0] - 1.0) )); // FT[Xa] factory trim calculation 00177 factoryTrim[1] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[1] - 1.0) )); // FT[Ya] factory trim calculation 00178 factoryTrim[2] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[2] - 1.0) )); // FT[Za] factory trim calculation 00179 factoryTrim[3] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[3] - 1.0) )); // FT[Xg] factory trim calculation 00180 factoryTrim[4] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[4] - 1.0) )); // FT[Yg] factory trim calculation 00181 factoryTrim[5] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[5] - 1.0) )); // FT[Zg] factory trim calculation 00182 00183 // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response 00184 // To get percent, must multiply by 100 00185 for (int i = 0; i < 3; i++) { 00186 destination[i] = 100.0*((float)(aSTAvg[i] - aAvg[i]))/factoryTrim[i]; // Report percent differences 00187 destination[i+3] = 100.0*((float)(gSTAvg[i] - gAvg[i]))/factoryTrim[i+3]; // Report percent differences 00188 } 00189 } 00190 00191 void MPU9250::pickupAccel(float accel[3]){ 00192 sensingAccel(); 00193 accel[0] = ax; 00194 accel[1] = ay; 00195 accel[2] = az; 00196 } 00197 00198 void MPU9250::pickupGyro(float gyro[3]){ 00199 sensingGyro(); 00200 gyro[0] = gx; 00201 gyro[1] = gy; 00202 gyro[2] = gz; 00203 } 00204 00205 void MPU9250::pickupMag(float mag[3]){ 00206 sensingMag(); 00207 mag[0] = mx; 00208 mag[1] = my; 00209 mag[2] = mz; 00210 } 00211 00212 float MPU9250::pickupTemp(void){ 00213 sensingTemp(); 00214 return temperature; 00215 } 00216 00217 void MPU9250::displayAccel(void){ 00218 pc_p->printf("ax = %f", 1000*ax); 00219 pc_p->printf(" ay = %f", 1000*ay); 00220 pc_p->printf(" az = %f mg\n\r", 1000*az); 00221 } 00222 00223 void MPU9250::displayGyro(void){ 00224 pc_p->printf("gx = %f", gx); 00225 pc_p->printf(" gy = %f", gy); 00226 pc_p->printf(" gz = %f deg/s\n\r", gz); 00227 } 00228 00229 void MPU9250::displayMag(void){ 00230 pc_p->printf("mx = %f,", mx); 00231 pc_p->printf(" my = %f,", my); 00232 pc_p->printf(" mz = %f mG\n\r", mz); 00233 } 00234 00235 void MPU9250::displayQuaternion(void){ 00236 pc_p->printf("q0 = %f\n\r", q[0]); 00237 pc_p->printf("q1 = %f\n\r", q[1]); 00238 pc_p->printf("q2 = %f\n\r", q[2]); 00239 pc_p->printf("q3 = %f\n\r", q[3]); 00240 } 00241 00242 void MPU9250::displayAngle(void){ 00243 //pc_p->printf("$%d %d %d;",(int)(yaw*100),(int)(pitch*100),(int)(roll*100)); 00244 pc_p->printf("Roll: %f\tPitch: %f\tYaw: %f\n\r", roll, pitch, yaw); 00245 } 00246 00247 void MPU9250::displayTemperature(void){ 00248 pc_p->printf(" temperature = %f C\n\r", temperature); 00249 } 00250 00251 void MPU9250::setMagBias(float bias_x, float bias_y, float bias_z){ 00252 magbias[0] = bias_x; 00253 magbias[1] = bias_y; 00254 magbias[2] = bias_z; 00255 } 00256 00257 /*---------- private function ----------*/ 00258 00259 void MPU9250::writeByte(uint8_t address, uint8_t subAddress, uint8_t data) 00260 { 00261 char data_write[2]; 00262 00263 data_write[0] = subAddress; 00264 data_write[1] = data; 00265 i2c.write(address, data_write, 2, 0); 00266 } 00267 00268 char MPU9250::readByte(uint8_t address, uint8_t subAddress) 00269 { 00270 char data[1]; // `data` will store the register data 00271 char data_write[1]; 00272 00273 data_write[0] = subAddress; 00274 i2c.write(address, data_write, 1, 1); // no stop 00275 i2c.read(address, data, 1, 0); 00276 return data[0]; 00277 } 00278 00279 void MPU9250::readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) 00280 { 00281 char data[14]; 00282 char data_write[1]; 00283 00284 data_write[0] = subAddress; 00285 i2c.write(address, data_write, 1, 1); // no stop 00286 i2c.read(address, data, count, 0); 00287 for(int ii = 0; ii < count; ii++) { 00288 dest[ii] = data[ii]; 00289 } 00290 } 00291 00292 void MPU9250::initializeValue(void){ 00293 Ascale = AFS_2G; // AFS_2G, AFS_4G, AFS_8G, AFS_16G 00294 Gscale = GFS_250DPS; // GFS_250DPS, GFS_500DPS, GFS_1000DPS, GFS_2000DPS 00295 Mscale = MFS_16BITS; // MFS_14BITS or MFS_16BITS, 14-bit or 16-bit magnetometer resolution 00296 Mmode = 0x06; // Either 8 Hz 0x02) or 100 Hz (0x06) magnetometer data ODR 00297 00298 GyroMeasError = PI * (60.0f / 180.0f); 00299 beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta 00300 GyroMeasDrift = PI * (1.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) 00301 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 00302 00303 deltat = 0.0f; // integration interval for both filter schemes 00304 lastUpdate = 0, firstUpdate = 0, Now = 0; // used to calculate integration interval // used to calculate integration interval 00305 00306 for(int i=0; i<3; i++){ 00307 magCalibration[i] = 0; 00308 gyroBias[i] = 0; 00309 accelBias[i] = 0; 00310 magbias[i] = 0; 00311 00312 eInt[i] = 0.0f; 00313 00314 lpmag[i] = 0.0f; 00315 } 00316 00317 q[0] = 1.0f; 00318 q[1] = 0.0f; 00319 q[2] = 0.0f; 00320 q[3] = 0.0f; 00321 } 00322 00323 void MPU9250::initMPU9250(void) 00324 { 00325 // Initialize MPU9250 device 00326 // wake up device 00327 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors 00328 wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt 00329 00330 // get stable time source 00331 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 00332 00333 // Configure Gyro and Accelerometer 00334 // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively; 00335 // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both 00336 // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate 00337 writeByte(MPU9250_ADDRESS, CONFIG, 0x03); 00338 00339 // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV) 00340 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above 00341 00342 // Set gyroscope full scale range 00343 // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3 00344 uint8_t c = readByte(MPU9250_ADDRESS, GYRO_CONFIG); // get current GYRO_CONFIG register value 00345 // c = c & ~0xE0; // Clear self-test bits [7:5] 00346 c = c & ~0x02; // Clear Fchoice bits [1:0] 00347 c = c & ~0x18; // Clear AFS bits [4:3] 00348 c = c | Gscale << 3; // Set full scale range for the gyro 00349 // c =| 0x00; // Set Fchoice for the gyro to 11 by writing its inverse to bits 1:0 of GYRO_CONFIG 00350 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c ); // Write new GYRO_CONFIG value to register 00351 00352 // Set accelerometer full-scale range configuration 00353 c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG); // get current ACCEL_CONFIG register value 00354 // c = c & ~0xE0; // Clear self-test bits [7:5] 00355 c = c & ~0x18; // Clear AFS bits [4:3] 00356 c = c | Ascale << 3; // Set full scale range for the accelerometer 00357 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c); // Write new ACCEL_CONFIG register value 00358 00359 // Set accelerometer sample rate configuration 00360 // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for 00361 // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz 00362 c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2); // get current ACCEL_CONFIG2 register value 00363 c = c & ~0x0F; // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0]) 00364 c = c | 0x03; // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz 00365 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c); // Write new ACCEL_CONFIG2 register value 00366 00367 // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates, 00368 // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting 00369 00370 // Configure Interrupts and Bypass Enable 00371 // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips 00372 // can join the I2C bus and all can be controlled by the Arduino as master 00373 writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22); 00374 writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt 00375 } 00376 00377 void MPU9250::initAK8963(float * destination) 00378 { 00379 // First extract the factory calibration for each magnetometer axis 00380 uint8_t rawData[3]; // x/y/z gyro calibration data stored here 00381 00382 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer 00383 wait(0.01); 00384 00385 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode 00386 wait(0.01); 00387 00388 readBytes(AK8963_ADDRESS, AK8963_ASAX, 3, &rawData[0]); // Read the x-, y-, and z-axis calibration values 00389 destination[0] = (float)(rawData[0] - 128)/256.0f + 1.0f; // Return x-axis sensitivity adjustment values, etc. 00390 destination[1] = (float)(rawData[1] - 128)/256.0f + 1.0f; 00391 destination[2] = (float)(rawData[2] - 128)/256.0f + 1.0f; 00392 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer 00393 wait(0.01); 00394 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_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR 00399 wait(0.01); 00400 } 00401 00402 void MPU9250::resetMPU9250(void) 00403 { 00404 // reset device 00405 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 00406 wait(0.1); 00407 } 00408 00409 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average 00410 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers. 00411 void MPU9250::calibrateMPU9250(float * dest1, float * dest2) 00412 { 00413 uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data 00414 uint16_t ii, packet_count, fifo_count; 00415 int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; 00416 int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases 00417 00418 // reset device, reset all registers, clear gyro and accelerometer bias registers 00419 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 00420 wait(0.1); 00421 00422 // get stable time source 00423 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 00424 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); 00425 writeByte(MPU9250_ADDRESS, PWR_MGMT_2, 0x00); 00426 wait(0.2); 00427 00428 // Configure device for bias calculation 00429 writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts 00430 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable FIFO 00431 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source 00432 writeByte(MPU9250_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master 00433 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes 00434 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP 00435 wait(0.015); 00436 00437 // Configure MPU9250 gyro and accelerometer for bias calculation 00438 writeByte(MPU9250_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz 00439 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz 00440 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity 00441 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity 00442 00443 uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec 00444 uint16_t accelsensitivity = 16384; // = 16384 LSB/g 00445 00446 // Configure FIFO to capture accelerometer and gyro data for bias calculation 00447 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x40); // Enable FIFO 00448 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 512 bytes in MPU-9250) 00449 wait(0.04); // accumulate 40 samples in 80 milliseconds = 480 bytes 00450 00451 // At end of sample accumulation, turn off FIFO sensor read 00452 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO 00453 readBytes(MPU9250_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count 00454 fifo_count = ((uint16_t)data[0] << 8) | data[1]; 00455 packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging 00456 00457 for (ii = 0; ii < packet_count; ii++) { 00458 int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0}; 00459 readBytes(MPU9250_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging 00460 accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO 00461 accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ; 00462 accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ; 00463 gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ; 00464 gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ; 00465 gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ; 00466 00467 accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases 00468 accel_bias[1] += (int32_t) accel_temp[1]; 00469 accel_bias[2] += (int32_t) accel_temp[2]; 00470 gyro_bias[0] += (int32_t) gyro_temp[0]; 00471 gyro_bias[1] += (int32_t) gyro_temp[1]; 00472 gyro_bias[2] += (int32_t) gyro_temp[2]; 00473 00474 } 00475 accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases 00476 accel_bias[1] /= (int32_t) packet_count; 00477 accel_bias[2] /= (int32_t) packet_count; 00478 gyro_bias[0] /= (int32_t) packet_count; 00479 gyro_bias[1] /= (int32_t) packet_count; 00480 gyro_bias[2] /= (int32_t) packet_count; 00481 00482 if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;} // Remove gravity from the z-axis accelerometer bias calculation 00483 else {accel_bias[2] += (int32_t) accelsensitivity;} 00484 00485 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup 00486 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 00487 data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases 00488 data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF; 00489 data[3] = (-gyro_bias[1]/4) & 0xFF; 00490 data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF; 00491 data[5] = (-gyro_bias[2]/4) & 0xFF; 00492 00493 /// Push gyro biases to hardware registers 00494 /* 00495 writeByte(MPU9250_ADDRESS, XG_OFFSET_H, data[0]); 00496 writeByte(MPU9250_ADDRESS, XG_OFFSET_L, data[1]); 00497 writeByte(MPU9250_ADDRESS, YG_OFFSET_H, data[2]); 00498 writeByte(MPU9250_ADDRESS, YG_OFFSET_L, data[3]); 00499 writeByte(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]); 00500 writeByte(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]); 00501 */ 00502 dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction 00503 dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity; 00504 dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity; 00505 00506 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain 00507 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold 00508 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature 00509 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that 00510 // the accelerometer biases calculated above must be divided by 8. 00511 00512 readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values 00513 accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00514 readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]); 00515 accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00516 readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]); 00517 accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00518 00519 uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers 00520 uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis 00521 00522 for(ii = 0; ii < 3; ii++) { 00523 if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit 00524 } 00525 00526 // Construct total accelerometer bias, including calculated average accelerometer bias from above 00527 accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale) 00528 accel_bias_reg[1] -= (accel_bias[1]/8); 00529 accel_bias_reg[2] -= (accel_bias[2]/8); 00530 00531 data[0] = (accel_bias_reg[0] >> 8) & 0xFF; 00532 data[1] = (accel_bias_reg[0]) & 0xFF; 00533 data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00534 data[2] = (accel_bias_reg[1] >> 8) & 0xFF; 00535 data[3] = (accel_bias_reg[1]) & 0xFF; 00536 data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00537 data[4] = (accel_bias_reg[2] >> 8) & 0xFF; 00538 data[5] = (accel_bias_reg[2]) & 0xFF; 00539 data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00540 00541 // Apparently this is not working for the acceleration biases in the MPU-9250 00542 // Are we handling the temperature correction bit properly? 00543 // Push accelerometer biases to hardware registers 00544 /* 00545 writeByte(MPU9250_ADDRESS, XA_OFFSET_H, data[0]); 00546 writeByte(MPU9250_ADDRESS, XA_OFFSET_L, data[1]); 00547 writeByte(MPU9250_ADDRESS, YA_OFFSET_H, data[2]); 00548 writeByte(MPU9250_ADDRESS, YA_OFFSET_L, data[3]); 00549 writeByte(MPU9250_ADDRESS, ZA_OFFSET_H, data[4]); 00550 writeByte(MPU9250_ADDRESS, ZA_OFFSET_L, data[5]); 00551 */ 00552 // Output scaled accelerometer biases for manual subtraction in the main program 00553 dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; 00554 dest2[1] = (float)accel_bias[1]/(float)accelsensitivity; 00555 dest2[2] = (float)accel_bias[2]/(float)accelsensitivity; 00556 } 00557 00558 void MPU9250::getMres(void) 00559 { 00560 switch (Mscale) 00561 { 00562 // Possible magnetometer scales (and their register bit settings) are: 00563 // 14 bit resolution (0) and 16 bit resolution (1) 00564 case MFS_14BITS: 00565 mRes = 10.0*4219.0/8190.0; // Proper scale to return milliGauss 00566 break; 00567 case MFS_16BITS: 00568 mRes = 10.0*4219.0/32760.0; // Proper scale to return milliGauss 00569 break; 00570 } 00571 } 00572 00573 void MPU9250::getGres(void) { 00574 switch (Gscale) 00575 { 00576 // Possible gyro scales (and their register bit settings) are: 00577 // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11). 00578 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 00579 case GFS_250DPS: 00580 gRes = 250.0/32768.0; 00581 break; 00582 case GFS_500DPS: 00583 gRes = 500.0/32768.0; 00584 break; 00585 case GFS_1000DPS: 00586 gRes = 1000.0/32768.0; 00587 break; 00588 case GFS_2000DPS: 00589 gRes = 2000.0/32768.0; 00590 break; 00591 } 00592 } 00593 00594 00595 void MPU9250::getAres(void) 00596 { 00597 switch (Ascale) 00598 { 00599 // Possible accelerometer scales (and their register bit settings) are: 00600 // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11). 00601 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 00602 case AFS_2G: 00603 aRes = 2.0/32768.0; 00604 break; 00605 case AFS_4G: 00606 aRes = 4.0/32768.0; 00607 break; 00608 case AFS_8G: 00609 aRes = 8.0/32768.0; 00610 break; 00611 case AFS_16G: 00612 aRes = 16.0/32768.0; 00613 break; 00614 } 00615 } 00616 00617 void MPU9250::readAccelData(int16_t * destination) 00618 { 00619 uint8_t rawData[6]; // x/y/z accel register data stored here 00620 00621 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 00622 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00623 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00624 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00625 } 00626 00627 void MPU9250::readGyroData(int16_t * destination) 00628 { 00629 uint8_t rawData[6]; // x/y/z gyro register data stored here 00630 00631 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 00632 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00633 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00634 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00635 } 00636 00637 void MPU9250::readMagData(int16_t * destination) 00638 { 00639 uint8_t rawData[7]; // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition 00640 00641 if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // wait for magnetometer data ready bit to be set 00642 readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]); // Read the six raw data and ST2 registers sequentially into data array 00643 uint8_t c = rawData[6]; // End data read by reading ST2 register 00644 if(!(c & 0x08)) { // Check if magnetic sensor overflow set, if not then report data 00645 destination[0] = (int16_t)(((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value 00646 destination[1] = (int16_t)(((int16_t)rawData[3] << 8) | rawData[2]) ; // Data stored as little Endian 00647 destination[2] = (int16_t)(((int16_t)rawData[5] << 8) | rawData[4]) ; 00648 } 00649 } 00650 } 00651 00652 int16_t MPU9250::readTempData(void) 00653 { 00654 uint8_t rawData[2]; // x/y/z gyro register data stored here 00655 00656 readBytes(MPU9250_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array 00657 00658 return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ; // Turn the MSB and LSB into a 16-bit value 00659 } 00660 00661 uint8_t MPU9250::Whoami_MPU9250(void){ 00662 return readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250); 00663 } 00664 00665 uint8_t MPU9250::Whoami_AK8963(void){ 00666 return readByte(WHO_AM_I_AK8963, WHO_AM_I_AK8963); 00667 } 00668 00669 void MPU9250::sensingAccel(void){ 00670 readAccelData(accelCount); 00671 ax = (float)accelCount[0]*aRes - accelBias[0]; 00672 ay = (float)accelCount[1]*aRes - accelBias[1]; 00673 az = (float)accelCount[2]*aRes - accelBias[2]; 00674 } 00675 00676 void MPU9250::sensingGyro(void){ 00677 readGyroData(gyroCount); 00678 gx = (float)gyroCount[0]*gRes - gyroBias[0]; 00679 gy = (float)gyroCount[1]*gRes - gyroBias[1]; 00680 gz = (float)gyroCount[2]*gRes - gyroBias[2]; 00681 } 00682 00683 void MPU9250::sensingMag(void){ 00684 readMagData(magCount); 00685 mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0]; 00686 my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1]; 00687 mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2]; 00688 } 00689 00690 void MPU9250::sensingTemp(void){ 00691 tempCount = readTempData(); 00692 temperature = ((float) tempCount) / 333.87f + 21.0f; // Temperature in degrees Centigrade 00693 } 00694 00695 // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" 00696 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details) 00697 // which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute 00698 // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc. 00699 // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms 00700 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz! 00701 void MPU9250::MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) 00702 { 00703 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability 00704 float norm; 00705 float hx, hy, _2bx, _2bz; 00706 float s1, s2, s3, s4; 00707 float qDot1, qDot2, qDot3, qDot4; 00708 00709 // Auxiliary variables to avoid repeated arithmetic 00710 float _2q1mx; 00711 float _2q1my; 00712 float _2q1mz; 00713 float _2q2mx; 00714 float _4bx; 00715 float _4bz; 00716 float _2q1 = 2.0f * q1; 00717 float _2q2 = 2.0f * q2; 00718 float _2q3 = 2.0f * q3; 00719 float _2q4 = 2.0f * q4; 00720 float _2q1q3 = 2.0f * q1 * q3; 00721 float _2q3q4 = 2.0f * q3 * q4; 00722 float q1q1 = q1 * q1; 00723 float q1q2 = q1 * q2; 00724 float q1q3 = q1 * q3; 00725 float q1q4 = q1 * q4; 00726 float q2q2 = q2 * q2; 00727 float q2q3 = q2 * q3; 00728 float q2q4 = q2 * q4; 00729 float q3q3 = q3 * q3; 00730 float q3q4 = q3 * q4; 00731 float q4q4 = q4 * q4; 00732 00733 // Normalise accelerometer measurement 00734 norm = sqrt(ax * ax + ay * ay + az * az); 00735 if (norm == 0.0f) return; // handle NaN 00736 norm = 1.0f/norm; 00737 ax *= norm; 00738 ay *= norm; 00739 az *= norm; 00740 00741 // Normalise magnetometer measurement 00742 norm = sqrt(mx * mx + my * my + mz * mz); 00743 if (norm == 0.0f) return; // handle NaN 00744 norm = 1.0f/norm; 00745 mx *= norm; 00746 my *= norm; 00747 mz *= norm; 00748 00749 // Reference direction of Earth's magnetic field 00750 _2q1mx = 2.0f * q1 * mx; 00751 _2q1my = 2.0f * q1 * my; 00752 _2q1mz = 2.0f * q1 * mz; 00753 _2q2mx = 2.0f * q2 * mx; 00754 hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4; 00755 hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4; 00756 _2bx = sqrt(hx * hx + hy * hy); 00757 _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4; 00758 _4bx = 2.0f * _2bx; 00759 _4bz = 2.0f * _2bz; 00760 00761 // Gradient decent algorithm corrective step 00762 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); 00763 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); 00764 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); 00765 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); 00766 norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude 00767 norm = 1.0f/norm; 00768 s1 *= norm; 00769 s2 *= norm; 00770 s3 *= norm; 00771 s4 *= norm; 00772 00773 // Compute rate of change of quaternion 00774 qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1; 00775 qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2; 00776 qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3; 00777 qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4; 00778 00779 // Integrate to yield quaternion 00780 q1 += qDot1 * deltat; 00781 q2 += qDot2 * deltat; 00782 q3 += qDot3 * deltat; 00783 q4 += qDot4 * deltat; 00784 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion 00785 norm = 1.0f/norm; 00786 q[0] = q1 * norm; 00787 q[1] = q2 * norm; 00788 q[2] = q3 * norm; 00789 q[3] = q4 * norm; 00790 00791 } 00792 00793 void MPU9250::MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) 00794 { 00795 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability 00796 float norm; 00797 float hx, hy, bx, bz; 00798 float vx, vy, vz, wx, wy, wz; 00799 float ex, ey, ez; 00800 float pa, pb, pc; 00801 00802 // Auxiliary variables to avoid repeated arithmetic 00803 float q1q1 = q1 * q1; 00804 float q1q2 = q1 * q2; 00805 float q1q3 = q1 * q3; 00806 float q1q4 = q1 * q4; 00807 float q2q2 = q2 * q2; 00808 float q2q3 = q2 * q3; 00809 float q2q4 = q2 * q4; 00810 float q3q3 = q3 * q3; 00811 float q3q4 = q3 * q4; 00812 float q4q4 = q4 * q4; 00813 00814 // Normalise accelerometer measurement 00815 norm = sqrt(ax * ax + ay * ay + az * az); 00816 if (norm == 0.0f) return; // handle NaN 00817 norm = 1.0f / norm; // use reciprocal for division 00818 ax *= norm; 00819 ay *= norm; 00820 az *= norm; 00821 00822 // Normalise magnetometer measurement 00823 norm = sqrt(mx * mx + my * my + mz * mz); 00824 if (norm == 0.0f) return; // handle NaN 00825 norm = 1.0f / norm; // use reciprocal for division 00826 mx *= norm; 00827 my *= norm; 00828 mz *= norm; 00829 00830 // Reference direction of Earth's magnetic field 00831 hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3); 00832 hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2); 00833 bx = sqrt((hx * hx) + (hy * hy)); 00834 bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3); 00835 00836 // Estimated direction of gravity and magnetic field 00837 vx = 2.0f * (q2q4 - q1q3); 00838 vy = 2.0f * (q1q2 + q3q4); 00839 vz = q1q1 - q2q2 - q3q3 + q4q4; 00840 wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3); 00841 wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4); 00842 wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3); 00843 00844 // Error is cross product between estimated direction and measured direction of gravity 00845 ex = (ay * vz - az * vy) + (my * wz - mz * wy); 00846 ey = (az * vx - ax * vz) + (mz * wx - mx * wz); 00847 ez = (ax * vy - ay * vx) + (mx * wy - my * wx); 00848 if (Ki > 0.0f){ 00849 eInt[0] += ex; // accumulate integral error 00850 eInt[1] += ey; 00851 eInt[2] += ez; 00852 00853 }else{ 00854 eInt[0] = 0.0f; // prevent integral wind up 00855 eInt[1] = 0.0f; 00856 eInt[2] = 0.0f; 00857 } 00858 00859 // Apply feedback terms 00860 gx = gx + Kp * ex + Ki * eInt[0]; 00861 gy = gy + Kp * ey + Ki * eInt[1]; 00862 gz = gz + Kp * ez + Ki * eInt[2]; 00863 00864 // Integrate rate of change of quaternion 00865 pa = q2; 00866 pb = q3; 00867 pc = q4; 00868 q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat); 00869 q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat); 00870 q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat); 00871 q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat); 00872 00873 // Normalise quaternion 00874 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); 00875 norm = 1.0f / norm; 00876 q[0] = q1 * norm; 00877 q[1] = q2 * norm; 00878 q[2] = q3 * norm; 00879 q[3] = q4 * norm; 00880 00881 } 00882 00883 void MPU9250::translateQuaternionToDeg(float quaternion[4]){ 00884 yaw = atan2(2.0f * (quaternion[1] * quaternion[2] + quaternion[0] * quaternion[3]), quaternion[0] * quaternion[0] + quaternion[1] * quaternion[1] - quaternion[2] * quaternion[2] - quaternion[3] * quaternion[3]); 00885 roll = -asin(2.0f * (quaternion[1] * quaternion[3] - quaternion[0] * quaternion[2])); 00886 pitch = atan2(2.0f * (quaternion[0] * quaternion[1] + quaternion[2] * quaternion[3]), quaternion[0] * quaternion[0] - quaternion[1] * quaternion[1] - quaternion[2] * quaternion[2] + quaternion[3] * quaternion[3]); 00887 } 00888 00889 void MPU9250::calibrateDegree(void){ 00890 pitch *= 180.0f / PI; 00891 yaw *= 180.0f / PI; 00892 yaw -= DECLINATION; 00893 roll *= 180.0f / PI; 00894 } 00895 00896 void MPU9250::transformCoordinateFromCompassToMPU(){ 00897 float buf = mx; 00898 mx = my; 00899 my = buf; 00900 mz = -mz; 00901 }
Generated on Wed Jul 13 2022 18:42:59 by
1.7.2