usb実装中

Dependencies:   mbed MPU6050_2 HMC5883L_2 SDFileSystem3

Committer:
Skykon
Date:
Wed Feb 06 11:49:05 2019 +0000
Revision:
3:c18342e4fddd
a

Who changed what in which revision?

UserRevisionLine numberNew contents of line
Skykon 3:c18342e4fddd 1 #include "mbed.h"
Skykon 3:c18342e4fddd 2 #include "math.h"
Skykon 3:c18342e4fddd 3 #include "MPU9250.h"
Skykon 3:c18342e4fddd 4
Skykon 3:c18342e4fddd 5
Skykon 3:c18342e4fddd 6 MPU9250::MPU9250(PinName sda, PinName scl, RawSerial* serial_p)
Skykon 3:c18342e4fddd 7 :
Skykon 3:c18342e4fddd 8 i2c_p(new I2C(sda,scl)),
Skykon 3:c18342e4fddd 9 i2c(*i2c_p),
Skykon 3:c18342e4fddd 10 pc_p(serial_p)
Skykon 3:c18342e4fddd 11 {
Skykon 3:c18342e4fddd 12 initializeValue();
Skykon 3:c18342e4fddd 13 }
Skykon 3:c18342e4fddd 14
Skykon 3:c18342e4fddd 15 MPU9250::~MPU9250(){}
Skykon 3:c18342e4fddd 16
Skykon 3:c18342e4fddd 17
Skykon 3:c18342e4fddd 18 /*---------- public function ----------*/
Skykon 3:c18342e4fddd 19 bool MPU9250::Initialize(void){
Skykon 3:c18342e4fddd 20 uint8_t whoami;
Skykon 3:c18342e4fddd 21
Skykon 3:c18342e4fddd 22 i2c.frequency(400000); // use fast (400 kHz) I2C
Skykon 3:c18342e4fddd 23 timer.start();
Skykon 3:c18342e4fddd 24
Skykon 3:c18342e4fddd 25 whoami = Whoami_MPU9250();
Skykon 3:c18342e4fddd 26 pc_p->printf("I AM 0x%x\n\r", whoami); pc_p->printf("I SHOULD BE 0x71\n\r");
Skykon 3:c18342e4fddd 27
Skykon 3:c18342e4fddd 28 if(whoami == IAM_MPU9250){
Skykon 3:c18342e4fddd 29 resetMPU9250(); // Reset registers to default in preparation for device calibration
Skykon 3:c18342e4fddd 30 calibrateMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers
Skykon 3:c18342e4fddd 31 wait(1);
Skykon 3:c18342e4fddd 32
Skykon 3:c18342e4fddd 33 initMPU9250();
Skykon 3:c18342e4fddd 34 initAK8963(magCalibration);
Skykon 3:c18342e4fddd 35
Skykon 3:c18342e4fddd 36 pc_p->printf("Accelerometer full-scale range = %f g\n\r", 2.0f*(float)(1<<Ascale));
Skykon 3:c18342e4fddd 37 pc_p->printf("Gyroscope full-scale range = %f deg/s\n\r", 250.0f*(float)(1<<Gscale));
Skykon 3:c18342e4fddd 38
Skykon 3:c18342e4fddd 39 if(Mscale == 0) pc_p->printf("Magnetometer resolution = 14 bits\n\r");
Skykon 3:c18342e4fddd 40 if(Mscale == 1) pc_p->printf("Magnetometer resolution = 16 bits\n\r");
Skykon 3:c18342e4fddd 41 if(Mmode == 2) pc_p->printf("Magnetometer ODR = 8 Hz\n\r");
Skykon 3:c18342e4fddd 42 if(Mmode == 6) pc_p->printf("Magnetometer ODR = 100 Hz\n\r");
Skykon 3:c18342e4fddd 43
Skykon 3:c18342e4fddd 44 getAres();
Skykon 3:c18342e4fddd 45 getGres();
Skykon 3:c18342e4fddd 46 getMres();
Skykon 3:c18342e4fddd 47
Skykon 3:c18342e4fddd 48 pc_p->printf("mpu9250 initialized\r\n");
Skykon 3:c18342e4fddd 49 return true;
Skykon 3:c18342e4fddd 50 }else return false;
Skykon 3:c18342e4fddd 51 }
Skykon 3:c18342e4fddd 52
Skykon 3:c18342e4fddd 53 bool MPU9250::sensingAcGyMg(){
Skykon 3:c18342e4fddd 54 if(readByte(MPU9250_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt
Skykon 3:c18342e4fddd 55 sensingAccel();
Skykon 3:c18342e4fddd 56 sensingGyro();
Skykon 3:c18342e4fddd 57 sensingMag();
Skykon 3:c18342e4fddd 58 return true;
Skykon 3:c18342e4fddd 59 }else return false;
Skykon 3:c18342e4fddd 60 }
Skykon 3:c18342e4fddd 61
Skykon 3:c18342e4fddd 62
Skykon 3:c18342e4fddd 63 void MPU9250::calculatePostureAngle(float degree[3]){
Skykon 3:c18342e4fddd 64 Now = timer.read_us();
Skykon 3:c18342e4fddd 65 deltat = (float)((Now - lastUpdate)/1000000.0f); // set integration time by time elapsed since last filter update
Skykon 3:c18342e4fddd 66 lastUpdate = Now;
Skykon 3:c18342e4fddd 67
Skykon 3:c18342e4fddd 68 // if(lastUpdate - firstUpdate > 10000000.0f) {
Skykon 3:c18342e4fddd 69 // beta = 0.04; // decrease filter gain after stabilized
Skykon 3:c18342e4fddd 70 // zeta = 0.015; // increasey bias drift gain after stabilized
Skykon 3:c18342e4fddd 71 // }
Skykon 3:c18342e4fddd 72
Skykon 3:c18342e4fddd 73 // Pass gyro rate as rad/s
Skykon 3:c18342e4fddd 74 MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
Skykon 3:c18342e4fddd 75 MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); //my, mx, mzになってるけどセンサの設置上の都合だろうか
Skykon 3:c18342e4fddd 76
Skykon 3:c18342e4fddd 77 // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation.
Skykon 3:c18342e4fddd 78 // In this coordinate system, the positive z-axis is down toward Earth.
Skykon 3:c18342e4fddd 79 // 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.
Skykon 3:c18342e4fddd 80 // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative.
Skykon 3:c18342e4fddd 81 // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll.
Skykon 3:c18342e4fddd 82 // These arise from the definition of the homogeneous rotation matrix constructed from quaternions.
Skykon 3:c18342e4fddd 83 // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be
Skykon 3:c18342e4fddd 84 // applied in the correct order which for this configuration is yaw, pitch, and then roll.
Skykon 3:c18342e4fddd 85 // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links.
Skykon 3:c18342e4fddd 86 translateQuaternionToDeg(q);
Skykon 3:c18342e4fddd 87 calibrateDegree();
Skykon 3:c18342e4fddd 88 degree[0] = roll;
Skykon 3:c18342e4fddd 89 degree[1] = pitch;
Skykon 3:c18342e4fddd 90 degree[2] = yaw;
Skykon 3:c18342e4fddd 91 }
Skykon 3:c18342e4fddd 92
Skykon 3:c18342e4fddd 93
Skykon 3:c18342e4fddd 94 float MPU9250::calculateYawByMg(){
Skykon 3:c18342e4fddd 95 transformCoordinateFromCompassToMPU();
Skykon 3:c18342e4fddd 96 lpmag[0] = LPGAIN_MAG *lpmag[0] + (1 - LPGAIN_MAG)*mx;
Skykon 3:c18342e4fddd 97 lpmag[1] = LPGAIN_MAG *lpmag[1] + (1 - LPGAIN_MAG)*my;
Skykon 3:c18342e4fddd 98 lpmag[2] = LPGAIN_MAG *lpmag[2] + (1 - LPGAIN_MAG)*mz;
Skykon 3:c18342e4fddd 99
Skykon 3:c18342e4fddd 100 float radroll = PI/180.0f * roll;
Skykon 3:c18342e4fddd 101 float radpitch = PI/180.0f * pitch;
Skykon 3:c18342e4fddd 102
Skykon 3:c18342e4fddd 103 return 180.0f/PI * atan2(lpmag[2]*sin(radpitch) - lpmag[1]*cos(radpitch),
Skykon 3:c18342e4fddd 104 lpmag[0]*cos(radroll) - lpmag[1]*sin(radroll)*sin(radpitch) + lpmag[2]*sin(radroll)*cos(radpitch));
Skykon 3:c18342e4fddd 105 }
Skykon 3:c18342e4fddd 106
Skykon 3:c18342e4fddd 107
Skykon 3:c18342e4fddd 108 // Accelerometer and gyroscope self test; check calibration wrt factory settings
Skykon 3:c18342e4fddd 109 void MPU9250::MPU9250SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass
Skykon 3:c18342e4fddd 110 {
Skykon 3:c18342e4fddd 111 uint8_t rawData[6] = {0, 0, 0, 0, 0, 0};
Skykon 3:c18342e4fddd 112 uint8_t selfTest[6];
Skykon 3:c18342e4fddd 113 int16_t gAvg[3], aAvg[3], aSTAvg[3], gSTAvg[3];
Skykon 3:c18342e4fddd 114 float factoryTrim[6];
Skykon 3:c18342e4fddd 115 uint8_t FS = 0;
Skykon 3:c18342e4fddd 116
Skykon 3:c18342e4fddd 117 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz
Skykon 3:c18342e4fddd 118 writeByte(MPU9250_ADDRESS, CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz
Skykon 3:c18342e4fddd 119 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 1<<FS); // Set full scale range for the gyro to 250 dps
Skykon 3:c18342e4fddd 120 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz
Skykon 3:c18342e4fddd 121 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 1<<FS); // Set full scale range for the accelerometer to 2 g
Skykon 3:c18342e4fddd 122
Skykon 3:c18342e4fddd 123 for( int ii = 0; ii < 200; ii++) { // get average current values of gyro and acclerometer
Skykon 3:c18342e4fddd 124 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
Skykon 3:c18342e4fddd 125 aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
Skykon 3:c18342e4fddd 126 aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
Skykon 3:c18342e4fddd 127 aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
Skykon 3:c18342e4fddd 128
Skykon 3:c18342e4fddd 129 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
Skykon 3:c18342e4fddd 130 gAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
Skykon 3:c18342e4fddd 131 gAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
Skykon 3:c18342e4fddd 132 gAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
Skykon 3:c18342e4fddd 133 }
Skykon 3:c18342e4fddd 134
Skykon 3:c18342e4fddd 135 for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average current readings
Skykon 3:c18342e4fddd 136 aAvg[ii] /= 200;
Skykon 3:c18342e4fddd 137 gAvg[ii] /= 200;
Skykon 3:c18342e4fddd 138 }
Skykon 3:c18342e4fddd 139
Skykon 3:c18342e4fddd 140 // Configure the accelerometer for self-test
Skykon 3:c18342e4fddd 141 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g
Skykon 3:c18342e4fddd 142 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s
Skykon 3:c18342e4fddd 143 //delay(55); // Delay a while to let the device stabilize
Skykon 3:c18342e4fddd 144
Skykon 3:c18342e4fddd 145 for( int ii = 0; ii < 200; ii++) { // get average self-test values of gyro and acclerometer
Skykon 3:c18342e4fddd 146 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
Skykon 3:c18342e4fddd 147 aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
Skykon 3:c18342e4fddd 148 aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
Skykon 3:c18342e4fddd 149 aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
Skykon 3:c18342e4fddd 150
Skykon 3:c18342e4fddd 151 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
Skykon 3:c18342e4fddd 152 gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
Skykon 3:c18342e4fddd 153 gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
Skykon 3:c18342e4fddd 154 gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
Skykon 3:c18342e4fddd 155 }
Skykon 3:c18342e4fddd 156
Skykon 3:c18342e4fddd 157 for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average self-test readings
Skykon 3:c18342e4fddd 158 aSTAvg[ii] /= 200;
Skykon 3:c18342e4fddd 159 gSTAvg[ii] /= 200;
Skykon 3:c18342e4fddd 160 }
Skykon 3:c18342e4fddd 161
Skykon 3:c18342e4fddd 162 // Configure the gyro and accelerometer for normal operation
Skykon 3:c18342e4fddd 163 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00);
Skykon 3:c18342e4fddd 164 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00);
Skykon 3:c18342e4fddd 165 //delay(45); // Delay a while to let the device stabilize
Skykon 3:c18342e4fddd 166
Skykon 3:c18342e4fddd 167 // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg
Skykon 3:c18342e4fddd 168 selfTest[0] = readByte(MPU9250_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results
Skykon 3:c18342e4fddd 169 selfTest[1] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_ACCEL); // Y-axis accel self-test results
Skykon 3:c18342e4fddd 170 selfTest[2] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_ACCEL); // Z-axis accel self-test results
Skykon 3:c18342e4fddd 171 selfTest[3] = readByte(MPU9250_ADDRESS, SELF_TEST_X_GYRO); // X-axis gyro self-test results
Skykon 3:c18342e4fddd 172 selfTest[4] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_GYRO); // Y-axis gyro self-test results
Skykon 3:c18342e4fddd 173 selfTest[5] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_GYRO); // Z-axis gyro self-test results
Skykon 3:c18342e4fddd 174
Skykon 3:c18342e4fddd 175 // Retrieve factory self-test value from self-test code reads
Skykon 3:c18342e4fddd 176 factoryTrim[0] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[0] - 1.0) )); // FT[Xa] factory trim calculation
Skykon 3:c18342e4fddd 177 factoryTrim[1] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[1] - 1.0) )); // FT[Ya] factory trim calculation
Skykon 3:c18342e4fddd 178 factoryTrim[2] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[2] - 1.0) )); // FT[Za] factory trim calculation
Skykon 3:c18342e4fddd 179 factoryTrim[3] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[3] - 1.0) )); // FT[Xg] factory trim calculation
Skykon 3:c18342e4fddd 180 factoryTrim[4] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[4] - 1.0) )); // FT[Yg] factory trim calculation
Skykon 3:c18342e4fddd 181 factoryTrim[5] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[5] - 1.0) )); // FT[Zg] factory trim calculation
Skykon 3:c18342e4fddd 182
Skykon 3:c18342e4fddd 183 // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response
Skykon 3:c18342e4fddd 184 // To get percent, must multiply by 100
Skykon 3:c18342e4fddd 185 for (int i = 0; i < 3; i++) {
Skykon 3:c18342e4fddd 186 destination[i] = 100.0*((float)(aSTAvg[i] - aAvg[i]))/factoryTrim[i]; // Report percent differences
Skykon 3:c18342e4fddd 187 destination[i+3] = 100.0*((float)(gSTAvg[i] - gAvg[i]))/factoryTrim[i+3]; // Report percent differences
Skykon 3:c18342e4fddd 188 }
Skykon 3:c18342e4fddd 189 }
Skykon 3:c18342e4fddd 190
Skykon 3:c18342e4fddd 191 void MPU9250::pickupAccel(float accel[3]){
Skykon 3:c18342e4fddd 192 sensingAccel();
Skykon 3:c18342e4fddd 193 accel[0] = ax;
Skykon 3:c18342e4fddd 194 accel[1] = ay;
Skykon 3:c18342e4fddd 195 accel[2] = az;
Skykon 3:c18342e4fddd 196 }
Skykon 3:c18342e4fddd 197
Skykon 3:c18342e4fddd 198 void MPU9250::pickupGyro(float gyro[3]){
Skykon 3:c18342e4fddd 199 sensingGyro();
Skykon 3:c18342e4fddd 200 gyro[0] = gx;
Skykon 3:c18342e4fddd 201 gyro[1] = gy;
Skykon 3:c18342e4fddd 202 gyro[2] = gz;
Skykon 3:c18342e4fddd 203 }
Skykon 3:c18342e4fddd 204
Skykon 3:c18342e4fddd 205 void MPU9250::pickupMag(float mag[3]){
Skykon 3:c18342e4fddd 206 sensingMag();
Skykon 3:c18342e4fddd 207 mag[0] = mx;
Skykon 3:c18342e4fddd 208 mag[1] = my;
Skykon 3:c18342e4fddd 209 mag[2] = mz;
Skykon 3:c18342e4fddd 210 }
Skykon 3:c18342e4fddd 211
Skykon 3:c18342e4fddd 212 float MPU9250::pickupTemp(void){
Skykon 3:c18342e4fddd 213 sensingTemp();
Skykon 3:c18342e4fddd 214 return temperature;
Skykon 3:c18342e4fddd 215 }
Skykon 3:c18342e4fddd 216
Skykon 3:c18342e4fddd 217 void MPU9250::displayAccel(void){
Skykon 3:c18342e4fddd 218 pc_p->printf("ax = %f", 1000*ax);
Skykon 3:c18342e4fddd 219 pc_p->printf(" ay = %f", 1000*ay);
Skykon 3:c18342e4fddd 220 pc_p->printf(" az = %f mg\n\r", 1000*az);
Skykon 3:c18342e4fddd 221 }
Skykon 3:c18342e4fddd 222
Skykon 3:c18342e4fddd 223 void MPU9250::displayGyro(void){
Skykon 3:c18342e4fddd 224 pc_p->printf("gx = %f", gx);
Skykon 3:c18342e4fddd 225 pc_p->printf(" gy = %f", gy);
Skykon 3:c18342e4fddd 226 pc_p->printf(" gz = %f deg/s\n\r", gz);
Skykon 3:c18342e4fddd 227 }
Skykon 3:c18342e4fddd 228
Skykon 3:c18342e4fddd 229 void MPU9250::displayMag(void){
Skykon 3:c18342e4fddd 230 pc_p->printf("mx = %f,", mx);
Skykon 3:c18342e4fddd 231 pc_p->printf(" my = %f,", my);
Skykon 3:c18342e4fddd 232 pc_p->printf(" mz = %f mG\n\r", mz);
Skykon 3:c18342e4fddd 233 }
Skykon 3:c18342e4fddd 234
Skykon 3:c18342e4fddd 235 void MPU9250::displayQuaternion(void){
Skykon 3:c18342e4fddd 236 pc_p->printf("q0 = %f\n\r", q[0]);
Skykon 3:c18342e4fddd 237 pc_p->printf("q1 = %f\n\r", q[1]);
Skykon 3:c18342e4fddd 238 pc_p->printf("q2 = %f\n\r", q[2]);
Skykon 3:c18342e4fddd 239 pc_p->printf("q3 = %f\n\r", q[3]);
Skykon 3:c18342e4fddd 240 }
Skykon 3:c18342e4fddd 241
Skykon 3:c18342e4fddd 242 void MPU9250::displayAngle(void){
Skykon 3:c18342e4fddd 243 //pc_p->printf("$%d %d %d;",(int)(yaw*100),(int)(pitch*100),(int)(roll*100));
Skykon 3:c18342e4fddd 244 pc_p->printf("Roll: %f\tPitch: %f\tYaw: %f\n\r", roll, pitch, yaw);
Skykon 3:c18342e4fddd 245 }
Skykon 3:c18342e4fddd 246
Skykon 3:c18342e4fddd 247 void MPU9250::displayTemperature(void){
Skykon 3:c18342e4fddd 248 pc_p->printf(" temperature = %f C\n\r", temperature);
Skykon 3:c18342e4fddd 249 }
Skykon 3:c18342e4fddd 250
Skykon 3:c18342e4fddd 251 void MPU9250::setMagBias(float bias_x, float bias_y, float bias_z){
Skykon 3:c18342e4fddd 252 magbias[0] = bias_x;
Skykon 3:c18342e4fddd 253 magbias[1] = bias_y;
Skykon 3:c18342e4fddd 254 magbias[2] = bias_z;
Skykon 3:c18342e4fddd 255 }
Skykon 3:c18342e4fddd 256
Skykon 3:c18342e4fddd 257 /*---------- private function ----------*/
Skykon 3:c18342e4fddd 258
Skykon 3:c18342e4fddd 259 void MPU9250::writeByte(uint8_t address, uint8_t subAddress, uint8_t data)
Skykon 3:c18342e4fddd 260 {
Skykon 3:c18342e4fddd 261 char data_write[2];
Skykon 3:c18342e4fddd 262
Skykon 3:c18342e4fddd 263 data_write[0] = subAddress;
Skykon 3:c18342e4fddd 264 data_write[1] = data;
Skykon 3:c18342e4fddd 265 i2c.write(address, data_write, 2, 0);
Skykon 3:c18342e4fddd 266 }
Skykon 3:c18342e4fddd 267
Skykon 3:c18342e4fddd 268 char MPU9250::readByte(uint8_t address, uint8_t subAddress)
Skykon 3:c18342e4fddd 269 {
Skykon 3:c18342e4fddd 270 char data[1]; // `data` will store the register data
Skykon 3:c18342e4fddd 271 char data_write[1];
Skykon 3:c18342e4fddd 272
Skykon 3:c18342e4fddd 273 data_write[0] = subAddress;
Skykon 3:c18342e4fddd 274 i2c.write(address, data_write, 1, 1); // no stop
Skykon 3:c18342e4fddd 275 i2c.read(address, data, 1, 0);
Skykon 3:c18342e4fddd 276 return data[0];
Skykon 3:c18342e4fddd 277 }
Skykon 3:c18342e4fddd 278
Skykon 3:c18342e4fddd 279 void MPU9250::readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest)
Skykon 3:c18342e4fddd 280 {
Skykon 3:c18342e4fddd 281 char data[14];
Skykon 3:c18342e4fddd 282 char data_write[1];
Skykon 3:c18342e4fddd 283
Skykon 3:c18342e4fddd 284 data_write[0] = subAddress;
Skykon 3:c18342e4fddd 285 i2c.write(address, data_write, 1, 1); // no stop
Skykon 3:c18342e4fddd 286 i2c.read(address, data, count, 0);
Skykon 3:c18342e4fddd 287 for(int ii = 0; ii < count; ii++) {
Skykon 3:c18342e4fddd 288 dest[ii] = data[ii];
Skykon 3:c18342e4fddd 289 }
Skykon 3:c18342e4fddd 290 }
Skykon 3:c18342e4fddd 291
Skykon 3:c18342e4fddd 292 void MPU9250::initializeValue(void){
Skykon 3:c18342e4fddd 293 Ascale = AFS_2G; // AFS_2G, AFS_4G, AFS_8G, AFS_16G
Skykon 3:c18342e4fddd 294 Gscale = GFS_250DPS; // GFS_250DPS, GFS_500DPS, GFS_1000DPS, GFS_2000DPS
Skykon 3:c18342e4fddd 295 Mscale = MFS_16BITS; // MFS_14BITS or MFS_16BITS, 14-bit or 16-bit magnetometer resolution
Skykon 3:c18342e4fddd 296 Mmode = 0x06; // Either 8 Hz 0x02) or 100 Hz (0x06) magnetometer data ODR
Skykon 3:c18342e4fddd 297
Skykon 3:c18342e4fddd 298 GyroMeasError = PI * (60.0f / 180.0f);
Skykon 3:c18342e4fddd 299 beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta
Skykon 3:c18342e4fddd 300 GyroMeasDrift = PI * (1.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s)
Skykon 3:c18342e4fddd 301 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
Skykon 3:c18342e4fddd 302
Skykon 3:c18342e4fddd 303 deltat = 0.0f; // integration interval for both filter schemes
Skykon 3:c18342e4fddd 304 lastUpdate = 0, firstUpdate = 0, Now = 0; // used to calculate integration interval // used to calculate integration interval
Skykon 3:c18342e4fddd 305
Skykon 3:c18342e4fddd 306 for(int i=0; i<3; i++){
Skykon 3:c18342e4fddd 307 magCalibration[i] = 0;
Skykon 3:c18342e4fddd 308 gyroBias[i] = 0;
Skykon 3:c18342e4fddd 309 accelBias[i] = 0;
Skykon 3:c18342e4fddd 310 magbias[i] = 0;
Skykon 3:c18342e4fddd 311
Skykon 3:c18342e4fddd 312 eInt[i] = 0.0f;
Skykon 3:c18342e4fddd 313
Skykon 3:c18342e4fddd 314 lpmag[i] = 0.0f;
Skykon 3:c18342e4fddd 315 }
Skykon 3:c18342e4fddd 316
Skykon 3:c18342e4fddd 317 q[0] = 1.0f;
Skykon 3:c18342e4fddd 318 q[1] = 0.0f;
Skykon 3:c18342e4fddd 319 q[2] = 0.0f;
Skykon 3:c18342e4fddd 320 q[3] = 0.0f;
Skykon 3:c18342e4fddd 321 }
Skykon 3:c18342e4fddd 322
Skykon 3:c18342e4fddd 323 void MPU9250::initMPU9250(void)
Skykon 3:c18342e4fddd 324 {
Skykon 3:c18342e4fddd 325 // Initialize MPU9250 device
Skykon 3:c18342e4fddd 326 // wake up device
Skykon 3:c18342e4fddd 327 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors
Skykon 3:c18342e4fddd 328 wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt
Skykon 3:c18342e4fddd 329
Skykon 3:c18342e4fddd 330 // get stable time source
Skykon 3:c18342e4fddd 331 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
Skykon 3:c18342e4fddd 332
Skykon 3:c18342e4fddd 333 // Configure Gyro and Accelerometer
Skykon 3:c18342e4fddd 334 // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively;
Skykon 3:c18342e4fddd 335 // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both
Skykon 3:c18342e4fddd 336 // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate
Skykon 3:c18342e4fddd 337 writeByte(MPU9250_ADDRESS, CONFIG, 0x03);
Skykon 3:c18342e4fddd 338
Skykon 3:c18342e4fddd 339 // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV)
Skykon 3:c18342e4fddd 340 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above
Skykon 3:c18342e4fddd 341
Skykon 3:c18342e4fddd 342 // Set gyroscope full scale range
Skykon 3:c18342e4fddd 343 // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3
Skykon 3:c18342e4fddd 344 uint8_t c = readByte(MPU9250_ADDRESS, GYRO_CONFIG); // get current GYRO_CONFIG register value
Skykon 3:c18342e4fddd 345 // c = c & ~0xE0; // Clear self-test bits [7:5]
Skykon 3:c18342e4fddd 346 c = c & ~0x02; // Clear Fchoice bits [1:0]
Skykon 3:c18342e4fddd 347 c = c & ~0x18; // Clear AFS bits [4:3]
Skykon 3:c18342e4fddd 348 c = c | Gscale << 3; // Set full scale range for the gyro
Skykon 3:c18342e4fddd 349 // c =| 0x00; // Set Fchoice for the gyro to 11 by writing its inverse to bits 1:0 of GYRO_CONFIG
Skykon 3:c18342e4fddd 350 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c ); // Write new GYRO_CONFIG value to register
Skykon 3:c18342e4fddd 351
Skykon 3:c18342e4fddd 352 // Set accelerometer full-scale range configuration
Skykon 3:c18342e4fddd 353 c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG); // get current ACCEL_CONFIG register value
Skykon 3:c18342e4fddd 354 // c = c & ~0xE0; // Clear self-test bits [7:5]
Skykon 3:c18342e4fddd 355 c = c & ~0x18; // Clear AFS bits [4:3]
Skykon 3:c18342e4fddd 356 c = c | Ascale << 3; // Set full scale range for the accelerometer
Skykon 3:c18342e4fddd 357 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c); // Write new ACCEL_CONFIG register value
Skykon 3:c18342e4fddd 358
Skykon 3:c18342e4fddd 359 // Set accelerometer sample rate configuration
Skykon 3:c18342e4fddd 360 // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for
Skykon 3:c18342e4fddd 361 // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz
Skykon 3:c18342e4fddd 362 c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2); // get current ACCEL_CONFIG2 register value
Skykon 3:c18342e4fddd 363 c = c & ~0x0F; // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0])
Skykon 3:c18342e4fddd 364 c = c | 0x03; // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz
Skykon 3:c18342e4fddd 365 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c); // Write new ACCEL_CONFIG2 register value
Skykon 3:c18342e4fddd 366
Skykon 3:c18342e4fddd 367 // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates,
Skykon 3:c18342e4fddd 368 // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting
Skykon 3:c18342e4fddd 369
Skykon 3:c18342e4fddd 370 // Configure Interrupts and Bypass Enable
Skykon 3:c18342e4fddd 371 // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips
Skykon 3:c18342e4fddd 372 // can join the I2C bus and all can be controlled by the Arduino as master
Skykon 3:c18342e4fddd 373 writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22);
Skykon 3:c18342e4fddd 374 writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt
Skykon 3:c18342e4fddd 375 }
Skykon 3:c18342e4fddd 376
Skykon 3:c18342e4fddd 377 void MPU9250::initAK8963(float * destination)
Skykon 3:c18342e4fddd 378 {
Skykon 3:c18342e4fddd 379 // First extract the factory calibration for each magnetometer axis
Skykon 3:c18342e4fddd 380 uint8_t rawData[3]; // x/y/z gyro calibration data stored here
Skykon 3:c18342e4fddd 381
Skykon 3:c18342e4fddd 382 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer
Skykon 3:c18342e4fddd 383 wait(0.01);
Skykon 3:c18342e4fddd 384
Skykon 3:c18342e4fddd 385 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode
Skykon 3:c18342e4fddd 386 wait(0.01);
Skykon 3:c18342e4fddd 387
Skykon 3:c18342e4fddd 388 readBytes(AK8963_ADDRESS, AK8963_ASAX, 3, &rawData[0]); // Read the x-, y-, and z-axis calibration values
Skykon 3:c18342e4fddd 389 destination[0] = (float)(rawData[0] - 128)/256.0f + 1.0f; // Return x-axis sensitivity adjustment values, etc.
Skykon 3:c18342e4fddd 390 destination[1] = (float)(rawData[1] - 128)/256.0f + 1.0f;
Skykon 3:c18342e4fddd 391 destination[2] = (float)(rawData[2] - 128)/256.0f + 1.0f;
Skykon 3:c18342e4fddd 392 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer
Skykon 3:c18342e4fddd 393 wait(0.01);
Skykon 3:c18342e4fddd 394
Skykon 3:c18342e4fddd 395 // Configure the magnetometer for continuous read and highest resolution
Skykon 3:c18342e4fddd 396 // set Mscale bit 4 to 1 (0) to enable 16 (14) bit resolution in CNTL register,
Skykon 3:c18342e4fddd 397 // and enable continuous mode data acquisition Mmode (bits [3:0]), 0010 for 8 Hz and 0110 for 100 Hz sample rates
Skykon 3:c18342e4fddd 398 writeByte(AK8963_ADDRESS, AK8963_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR
Skykon 3:c18342e4fddd 399 wait(0.01);
Skykon 3:c18342e4fddd 400 }
Skykon 3:c18342e4fddd 401
Skykon 3:c18342e4fddd 402 void MPU9250::resetMPU9250(void)
Skykon 3:c18342e4fddd 403 {
Skykon 3:c18342e4fddd 404 // reset device
Skykon 3:c18342e4fddd 405 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
Skykon 3:c18342e4fddd 406 wait(0.1);
Skykon 3:c18342e4fddd 407 }
Skykon 3:c18342e4fddd 408
Skykon 3:c18342e4fddd 409 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average
Skykon 3:c18342e4fddd 410 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers.
Skykon 3:c18342e4fddd 411 void MPU9250::calibrateMPU9250(float * dest1, float * dest2)
Skykon 3:c18342e4fddd 412 {
Skykon 3:c18342e4fddd 413 uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data
Skykon 3:c18342e4fddd 414 uint16_t ii, packet_count, fifo_count;
Skykon 3:c18342e4fddd 415 int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0};
Skykon 3:c18342e4fddd 416 int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases
Skykon 3:c18342e4fddd 417
Skykon 3:c18342e4fddd 418 // reset device, reset all registers, clear gyro and accelerometer bias registers
Skykon 3:c18342e4fddd 419 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
Skykon 3:c18342e4fddd 420 wait(0.1);
Skykon 3:c18342e4fddd 421
Skykon 3:c18342e4fddd 422 // get stable time source
Skykon 3:c18342e4fddd 423 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
Skykon 3:c18342e4fddd 424 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01);
Skykon 3:c18342e4fddd 425 writeByte(MPU9250_ADDRESS, PWR_MGMT_2, 0x00);
Skykon 3:c18342e4fddd 426 wait(0.2);
Skykon 3:c18342e4fddd 427
Skykon 3:c18342e4fddd 428 // Configure device for bias calculation
Skykon 3:c18342e4fddd 429 writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts
Skykon 3:c18342e4fddd 430 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable FIFO
Skykon 3:c18342e4fddd 431 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source
Skykon 3:c18342e4fddd 432 writeByte(MPU9250_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master
Skykon 3:c18342e4fddd 433 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes
Skykon 3:c18342e4fddd 434 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP
Skykon 3:c18342e4fddd 435 wait(0.015);
Skykon 3:c18342e4fddd 436
Skykon 3:c18342e4fddd 437 // Configure MPU9250 gyro and accelerometer for bias calculation
Skykon 3:c18342e4fddd 438 writeByte(MPU9250_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz
Skykon 3:c18342e4fddd 439 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz
Skykon 3:c18342e4fddd 440 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity
Skykon 3:c18342e4fddd 441 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity
Skykon 3:c18342e4fddd 442
Skykon 3:c18342e4fddd 443 uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec
Skykon 3:c18342e4fddd 444 uint16_t accelsensitivity = 16384; // = 16384 LSB/g
Skykon 3:c18342e4fddd 445
Skykon 3:c18342e4fddd 446 // Configure FIFO to capture accelerometer and gyro data for bias calculation
Skykon 3:c18342e4fddd 447 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x40); // Enable FIFO
Skykon 3:c18342e4fddd 448 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 512 bytes in MPU-9250)
Skykon 3:c18342e4fddd 449 wait(0.04); // accumulate 40 samples in 80 milliseconds = 480 bytes
Skykon 3:c18342e4fddd 450
Skykon 3:c18342e4fddd 451 // At end of sample accumulation, turn off FIFO sensor read
Skykon 3:c18342e4fddd 452 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO
Skykon 3:c18342e4fddd 453 readBytes(MPU9250_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count
Skykon 3:c18342e4fddd 454 fifo_count = ((uint16_t)data[0] << 8) | data[1];
Skykon 3:c18342e4fddd 455 packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging
Skykon 3:c18342e4fddd 456
Skykon 3:c18342e4fddd 457 for (ii = 0; ii < packet_count; ii++) {
Skykon 3:c18342e4fddd 458 int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0};
Skykon 3:c18342e4fddd 459 readBytes(MPU9250_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging
Skykon 3:c18342e4fddd 460 accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO
Skykon 3:c18342e4fddd 461 accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ;
Skykon 3:c18342e4fddd 462 accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ;
Skykon 3:c18342e4fddd 463 gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ;
Skykon 3:c18342e4fddd 464 gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ;
Skykon 3:c18342e4fddd 465 gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ;
Skykon 3:c18342e4fddd 466
Skykon 3:c18342e4fddd 467 accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases
Skykon 3:c18342e4fddd 468 accel_bias[1] += (int32_t) accel_temp[1];
Skykon 3:c18342e4fddd 469 accel_bias[2] += (int32_t) accel_temp[2];
Skykon 3:c18342e4fddd 470 gyro_bias[0] += (int32_t) gyro_temp[0];
Skykon 3:c18342e4fddd 471 gyro_bias[1] += (int32_t) gyro_temp[1];
Skykon 3:c18342e4fddd 472 gyro_bias[2] += (int32_t) gyro_temp[2];
Skykon 3:c18342e4fddd 473
Skykon 3:c18342e4fddd 474 }
Skykon 3:c18342e4fddd 475 accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases
Skykon 3:c18342e4fddd 476 accel_bias[1] /= (int32_t) packet_count;
Skykon 3:c18342e4fddd 477 accel_bias[2] /= (int32_t) packet_count;
Skykon 3:c18342e4fddd 478 gyro_bias[0] /= (int32_t) packet_count;
Skykon 3:c18342e4fddd 479 gyro_bias[1] /= (int32_t) packet_count;
Skykon 3:c18342e4fddd 480 gyro_bias[2] /= (int32_t) packet_count;
Skykon 3:c18342e4fddd 481
Skykon 3:c18342e4fddd 482 if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;} // Remove gravity from the z-axis accelerometer bias calculation
Skykon 3:c18342e4fddd 483 else {accel_bias[2] += (int32_t) accelsensitivity;}
Skykon 3:c18342e4fddd 484
Skykon 3:c18342e4fddd 485 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup
Skykon 3:c18342e4fddd 486 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
Skykon 3:c18342e4fddd 487 data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases
Skykon 3:c18342e4fddd 488 data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF;
Skykon 3:c18342e4fddd 489 data[3] = (-gyro_bias[1]/4) & 0xFF;
Skykon 3:c18342e4fddd 490 data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF;
Skykon 3:c18342e4fddd 491 data[5] = (-gyro_bias[2]/4) & 0xFF;
Skykon 3:c18342e4fddd 492
Skykon 3:c18342e4fddd 493 /// Push gyro biases to hardware registers
Skykon 3:c18342e4fddd 494 /*
Skykon 3:c18342e4fddd 495 writeByte(MPU9250_ADDRESS, XG_OFFSET_H, data[0]);
Skykon 3:c18342e4fddd 496 writeByte(MPU9250_ADDRESS, XG_OFFSET_L, data[1]);
Skykon 3:c18342e4fddd 497 writeByte(MPU9250_ADDRESS, YG_OFFSET_H, data[2]);
Skykon 3:c18342e4fddd 498 writeByte(MPU9250_ADDRESS, YG_OFFSET_L, data[3]);
Skykon 3:c18342e4fddd 499 writeByte(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]);
Skykon 3:c18342e4fddd 500 writeByte(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]);
Skykon 3:c18342e4fddd 501 */
Skykon 3:c18342e4fddd 502 dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction
Skykon 3:c18342e4fddd 503 dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity;
Skykon 3:c18342e4fddd 504 dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity;
Skykon 3:c18342e4fddd 505
Skykon 3:c18342e4fddd 506 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain
Skykon 3:c18342e4fddd 507 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold
Skykon 3:c18342e4fddd 508 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature
Skykon 3:c18342e4fddd 509 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that
Skykon 3:c18342e4fddd 510 // the accelerometer biases calculated above must be divided by 8.
Skykon 3:c18342e4fddd 511
Skykon 3:c18342e4fddd 512 readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values
Skykon 3:c18342e4fddd 513 accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1];
Skykon 3:c18342e4fddd 514 readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]);
Skykon 3:c18342e4fddd 515 accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1];
Skykon 3:c18342e4fddd 516 readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]);
Skykon 3:c18342e4fddd 517 accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1];
Skykon 3:c18342e4fddd 518
Skykon 3:c18342e4fddd 519 uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers
Skykon 3:c18342e4fddd 520 uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis
Skykon 3:c18342e4fddd 521
Skykon 3:c18342e4fddd 522 for(ii = 0; ii < 3; ii++) {
Skykon 3:c18342e4fddd 523 if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit
Skykon 3:c18342e4fddd 524 }
Skykon 3:c18342e4fddd 525
Skykon 3:c18342e4fddd 526 // Construct total accelerometer bias, including calculated average accelerometer bias from above
Skykon 3:c18342e4fddd 527 accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale)
Skykon 3:c18342e4fddd 528 accel_bias_reg[1] -= (accel_bias[1]/8);
Skykon 3:c18342e4fddd 529 accel_bias_reg[2] -= (accel_bias[2]/8);
Skykon 3:c18342e4fddd 530
Skykon 3:c18342e4fddd 531 data[0] = (accel_bias_reg[0] >> 8) & 0xFF;
Skykon 3:c18342e4fddd 532 data[1] = (accel_bias_reg[0]) & 0xFF;
Skykon 3:c18342e4fddd 533 data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers
Skykon 3:c18342e4fddd 534 data[2] = (accel_bias_reg[1] >> 8) & 0xFF;
Skykon 3:c18342e4fddd 535 data[3] = (accel_bias_reg[1]) & 0xFF;
Skykon 3:c18342e4fddd 536 data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers
Skykon 3:c18342e4fddd 537 data[4] = (accel_bias_reg[2] >> 8) & 0xFF;
Skykon 3:c18342e4fddd 538 data[5] = (accel_bias_reg[2]) & 0xFF;
Skykon 3:c18342e4fddd 539 data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers
Skykon 3:c18342e4fddd 540
Skykon 3:c18342e4fddd 541 // Apparently this is not working for the acceleration biases in the MPU-9250
Skykon 3:c18342e4fddd 542 // Are we handling the temperature correction bit properly?
Skykon 3:c18342e4fddd 543 // Push accelerometer biases to hardware registers
Skykon 3:c18342e4fddd 544 /*
Skykon 3:c18342e4fddd 545 writeByte(MPU9250_ADDRESS, XA_OFFSET_H, data[0]);
Skykon 3:c18342e4fddd 546 writeByte(MPU9250_ADDRESS, XA_OFFSET_L, data[1]);
Skykon 3:c18342e4fddd 547 writeByte(MPU9250_ADDRESS, YA_OFFSET_H, data[2]);
Skykon 3:c18342e4fddd 548 writeByte(MPU9250_ADDRESS, YA_OFFSET_L, data[3]);
Skykon 3:c18342e4fddd 549 writeByte(MPU9250_ADDRESS, ZA_OFFSET_H, data[4]);
Skykon 3:c18342e4fddd 550 writeByte(MPU9250_ADDRESS, ZA_OFFSET_L, data[5]);
Skykon 3:c18342e4fddd 551 */
Skykon 3:c18342e4fddd 552 // Output scaled accelerometer biases for manual subtraction in the main program
Skykon 3:c18342e4fddd 553 dest2[0] = (float)accel_bias[0]/(float)accelsensitivity;
Skykon 3:c18342e4fddd 554 dest2[1] = (float)accel_bias[1]/(float)accelsensitivity;
Skykon 3:c18342e4fddd 555 dest2[2] = (float)accel_bias[2]/(float)accelsensitivity;
Skykon 3:c18342e4fddd 556 }
Skykon 3:c18342e4fddd 557
Skykon 3:c18342e4fddd 558 void MPU9250::getMres(void)
Skykon 3:c18342e4fddd 559 {
Skykon 3:c18342e4fddd 560 switch (Mscale)
Skykon 3:c18342e4fddd 561 {
Skykon 3:c18342e4fddd 562 // Possible magnetometer scales (and their register bit settings) are:
Skykon 3:c18342e4fddd 563 // 14 bit resolution (0) and 16 bit resolution (1)
Skykon 3:c18342e4fddd 564 case MFS_14BITS:
Skykon 3:c18342e4fddd 565 mRes = 10.0*4219.0/8190.0; // Proper scale to return milliGauss
Skykon 3:c18342e4fddd 566 break;
Skykon 3:c18342e4fddd 567 case MFS_16BITS:
Skykon 3:c18342e4fddd 568 mRes = 10.0*4219.0/32760.0; // Proper scale to return milliGauss
Skykon 3:c18342e4fddd 569 break;
Skykon 3:c18342e4fddd 570 }
Skykon 3:c18342e4fddd 571 }
Skykon 3:c18342e4fddd 572
Skykon 3:c18342e4fddd 573 void MPU9250::getGres(void) {
Skykon 3:c18342e4fddd 574 switch (Gscale)
Skykon 3:c18342e4fddd 575 {
Skykon 3:c18342e4fddd 576 // Possible gyro scales (and their register bit settings) are:
Skykon 3:c18342e4fddd 577 // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11).
Skykon 3:c18342e4fddd 578 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
Skykon 3:c18342e4fddd 579 case GFS_250DPS:
Skykon 3:c18342e4fddd 580 gRes = 250.0/32768.0;
Skykon 3:c18342e4fddd 581 break;
Skykon 3:c18342e4fddd 582 case GFS_500DPS:
Skykon 3:c18342e4fddd 583 gRes = 500.0/32768.0;
Skykon 3:c18342e4fddd 584 break;
Skykon 3:c18342e4fddd 585 case GFS_1000DPS:
Skykon 3:c18342e4fddd 586 gRes = 1000.0/32768.0;
Skykon 3:c18342e4fddd 587 break;
Skykon 3:c18342e4fddd 588 case GFS_2000DPS:
Skykon 3:c18342e4fddd 589 gRes = 2000.0/32768.0;
Skykon 3:c18342e4fddd 590 break;
Skykon 3:c18342e4fddd 591 }
Skykon 3:c18342e4fddd 592 }
Skykon 3:c18342e4fddd 593
Skykon 3:c18342e4fddd 594
Skykon 3:c18342e4fddd 595 void MPU9250::getAres(void)
Skykon 3:c18342e4fddd 596 {
Skykon 3:c18342e4fddd 597 switch (Ascale)
Skykon 3:c18342e4fddd 598 {
Skykon 3:c18342e4fddd 599 // Possible accelerometer scales (and their register bit settings) are:
Skykon 3:c18342e4fddd 600 // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11).
Skykon 3:c18342e4fddd 601 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
Skykon 3:c18342e4fddd 602 case AFS_2G:
Skykon 3:c18342e4fddd 603 aRes = 2.0/32768.0;
Skykon 3:c18342e4fddd 604 break;
Skykon 3:c18342e4fddd 605 case AFS_4G:
Skykon 3:c18342e4fddd 606 aRes = 4.0/32768.0;
Skykon 3:c18342e4fddd 607 break;
Skykon 3:c18342e4fddd 608 case AFS_8G:
Skykon 3:c18342e4fddd 609 aRes = 8.0/32768.0;
Skykon 3:c18342e4fddd 610 break;
Skykon 3:c18342e4fddd 611 case AFS_16G:
Skykon 3:c18342e4fddd 612 aRes = 16.0/32768.0;
Skykon 3:c18342e4fddd 613 break;
Skykon 3:c18342e4fddd 614 }
Skykon 3:c18342e4fddd 615 }
Skykon 3:c18342e4fddd 616
Skykon 3:c18342e4fddd 617 void MPU9250::readAccelData(int16_t * destination)
Skykon 3:c18342e4fddd 618 {
Skykon 3:c18342e4fddd 619 uint8_t rawData[6]; // x/y/z accel register data stored here
Skykon 3:c18342e4fddd 620
Skykon 3:c18342e4fddd 621 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
Skykon 3:c18342e4fddd 622 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
Skykon 3:c18342e4fddd 623 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
Skykon 3:c18342e4fddd 624 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
Skykon 3:c18342e4fddd 625 }
Skykon 3:c18342e4fddd 626
Skykon 3:c18342e4fddd 627 void MPU9250::readGyroData(int16_t * destination)
Skykon 3:c18342e4fddd 628 {
Skykon 3:c18342e4fddd 629 uint8_t rawData[6]; // x/y/z gyro register data stored here
Skykon 3:c18342e4fddd 630
Skykon 3:c18342e4fddd 631 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
Skykon 3:c18342e4fddd 632 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
Skykon 3:c18342e4fddd 633 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
Skykon 3:c18342e4fddd 634 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
Skykon 3:c18342e4fddd 635 }
Skykon 3:c18342e4fddd 636
Skykon 3:c18342e4fddd 637 void MPU9250::readMagData(int16_t * destination)
Skykon 3:c18342e4fddd 638 {
Skykon 3:c18342e4fddd 639 uint8_t rawData[7]; // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition
Skykon 3:c18342e4fddd 640
Skykon 3:c18342e4fddd 641 if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // wait for magnetometer data ready bit to be set
Skykon 3:c18342e4fddd 642 readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]); // Read the six raw data and ST2 registers sequentially into data array
Skykon 3:c18342e4fddd 643 uint8_t c = rawData[6]; // End data read by reading ST2 register
Skykon 3:c18342e4fddd 644 if(!(c & 0x08)) { // Check if magnetic sensor overflow set, if not then report data
Skykon 3:c18342e4fddd 645 destination[0] = (int16_t)(((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value
Skykon 3:c18342e4fddd 646 destination[1] = (int16_t)(((int16_t)rawData[3] << 8) | rawData[2]) ; // Data stored as little Endian
Skykon 3:c18342e4fddd 647 destination[2] = (int16_t)(((int16_t)rawData[5] << 8) | rawData[4]) ;
Skykon 3:c18342e4fddd 648 }
Skykon 3:c18342e4fddd 649 }
Skykon 3:c18342e4fddd 650 }
Skykon 3:c18342e4fddd 651
Skykon 3:c18342e4fddd 652 int16_t MPU9250::readTempData(void)
Skykon 3:c18342e4fddd 653 {
Skykon 3:c18342e4fddd 654 uint8_t rawData[2]; // x/y/z gyro register data stored here
Skykon 3:c18342e4fddd 655
Skykon 3:c18342e4fddd 656 readBytes(MPU9250_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array
Skykon 3:c18342e4fddd 657
Skykon 3:c18342e4fddd 658 return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ; // Turn the MSB and LSB into a 16-bit value
Skykon 3:c18342e4fddd 659 }
Skykon 3:c18342e4fddd 660
Skykon 3:c18342e4fddd 661 uint8_t MPU9250::Whoami_MPU9250(void){
Skykon 3:c18342e4fddd 662 return readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250);
Skykon 3:c18342e4fddd 663 }
Skykon 3:c18342e4fddd 664
Skykon 3:c18342e4fddd 665 uint8_t MPU9250::Whoami_AK8963(void){
Skykon 3:c18342e4fddd 666 return readByte(WHO_AM_I_AK8963, WHO_AM_I_AK8963);
Skykon 3:c18342e4fddd 667 }
Skykon 3:c18342e4fddd 668
Skykon 3:c18342e4fddd 669 void MPU9250::sensingAccel(void){
Skykon 3:c18342e4fddd 670 readAccelData(accelCount);
Skykon 3:c18342e4fddd 671 ax = (float)accelCount[0]*aRes - accelBias[0];
Skykon 3:c18342e4fddd 672 ay = (float)accelCount[1]*aRes - accelBias[1];
Skykon 3:c18342e4fddd 673 az = (float)accelCount[2]*aRes - accelBias[2];
Skykon 3:c18342e4fddd 674 }
Skykon 3:c18342e4fddd 675
Skykon 3:c18342e4fddd 676 void MPU9250::sensingGyro(void){
Skykon 3:c18342e4fddd 677 readGyroData(gyroCount);
Skykon 3:c18342e4fddd 678 gx = (float)gyroCount[0]*gRes - gyroBias[0];
Skykon 3:c18342e4fddd 679 gy = (float)gyroCount[1]*gRes - gyroBias[1];
Skykon 3:c18342e4fddd 680 gz = (float)gyroCount[2]*gRes - gyroBias[2];
Skykon 3:c18342e4fddd 681 }
Skykon 3:c18342e4fddd 682
Skykon 3:c18342e4fddd 683 void MPU9250::sensingMag(void){
Skykon 3:c18342e4fddd 684 readMagData(magCount);
Skykon 3:c18342e4fddd 685 mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0];
Skykon 3:c18342e4fddd 686 my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1];
Skykon 3:c18342e4fddd 687 mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2];
Skykon 3:c18342e4fddd 688 }
Skykon 3:c18342e4fddd 689
Skykon 3:c18342e4fddd 690 void MPU9250::sensingTemp(void){
Skykon 3:c18342e4fddd 691 tempCount = readTempData();
Skykon 3:c18342e4fddd 692 temperature = ((float) tempCount) / 333.87f + 21.0f; // Temperature in degrees Centigrade
Skykon 3:c18342e4fddd 693 }
Skykon 3:c18342e4fddd 694
Skykon 3:c18342e4fddd 695 // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays"
Skykon 3:c18342e4fddd 696 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details)
Skykon 3:c18342e4fddd 697 // which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute
Skykon 3:c18342e4fddd 698 // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc.
Skykon 3:c18342e4fddd 699 // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms
Skykon 3:c18342e4fddd 700 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz!
Skykon 3:c18342e4fddd 701 void MPU9250::MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
Skykon 3:c18342e4fddd 702 {
Skykon 3:c18342e4fddd 703 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability
Skykon 3:c18342e4fddd 704 float norm;
Skykon 3:c18342e4fddd 705 float hx, hy, _2bx, _2bz;
Skykon 3:c18342e4fddd 706 float s1, s2, s3, s4;
Skykon 3:c18342e4fddd 707 float qDot1, qDot2, qDot3, qDot4;
Skykon 3:c18342e4fddd 708
Skykon 3:c18342e4fddd 709 // Auxiliary variables to avoid repeated arithmetic
Skykon 3:c18342e4fddd 710 float _2q1mx;
Skykon 3:c18342e4fddd 711 float _2q1my;
Skykon 3:c18342e4fddd 712 float _2q1mz;
Skykon 3:c18342e4fddd 713 float _2q2mx;
Skykon 3:c18342e4fddd 714 float _4bx;
Skykon 3:c18342e4fddd 715 float _4bz;
Skykon 3:c18342e4fddd 716 float _2q1 = 2.0f * q1;
Skykon 3:c18342e4fddd 717 float _2q2 = 2.0f * q2;
Skykon 3:c18342e4fddd 718 float _2q3 = 2.0f * q3;
Skykon 3:c18342e4fddd 719 float _2q4 = 2.0f * q4;
Skykon 3:c18342e4fddd 720 float _2q1q3 = 2.0f * q1 * q3;
Skykon 3:c18342e4fddd 721 float _2q3q4 = 2.0f * q3 * q4;
Skykon 3:c18342e4fddd 722 float q1q1 = q1 * q1;
Skykon 3:c18342e4fddd 723 float q1q2 = q1 * q2;
Skykon 3:c18342e4fddd 724 float q1q3 = q1 * q3;
Skykon 3:c18342e4fddd 725 float q1q4 = q1 * q4;
Skykon 3:c18342e4fddd 726 float q2q2 = q2 * q2;
Skykon 3:c18342e4fddd 727 float q2q3 = q2 * q3;
Skykon 3:c18342e4fddd 728 float q2q4 = q2 * q4;
Skykon 3:c18342e4fddd 729 float q3q3 = q3 * q3;
Skykon 3:c18342e4fddd 730 float q3q4 = q3 * q4;
Skykon 3:c18342e4fddd 731 float q4q4 = q4 * q4;
Skykon 3:c18342e4fddd 732
Skykon 3:c18342e4fddd 733 // Normalise accelerometer measurement
Skykon 3:c18342e4fddd 734 norm = sqrt(ax * ax + ay * ay + az * az);
Skykon 3:c18342e4fddd 735 if (norm == 0.0f) return; // handle NaN
Skykon 3:c18342e4fddd 736 norm = 1.0f/norm;
Skykon 3:c18342e4fddd 737 ax *= norm;
Skykon 3:c18342e4fddd 738 ay *= norm;
Skykon 3:c18342e4fddd 739 az *= norm;
Skykon 3:c18342e4fddd 740
Skykon 3:c18342e4fddd 741 // Normalise magnetometer measurement
Skykon 3:c18342e4fddd 742 norm = sqrt(mx * mx + my * my + mz * mz);
Skykon 3:c18342e4fddd 743 if (norm == 0.0f) return; // handle NaN
Skykon 3:c18342e4fddd 744 norm = 1.0f/norm;
Skykon 3:c18342e4fddd 745 mx *= norm;
Skykon 3:c18342e4fddd 746 my *= norm;
Skykon 3:c18342e4fddd 747 mz *= norm;
Skykon 3:c18342e4fddd 748
Skykon 3:c18342e4fddd 749 // Reference direction of Earth's magnetic field
Skykon 3:c18342e4fddd 750 _2q1mx = 2.0f * q1 * mx;
Skykon 3:c18342e4fddd 751 _2q1my = 2.0f * q1 * my;
Skykon 3:c18342e4fddd 752 _2q1mz = 2.0f * q1 * mz;
Skykon 3:c18342e4fddd 753 _2q2mx = 2.0f * q2 * mx;
Skykon 3:c18342e4fddd 754 hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4;
Skykon 3:c18342e4fddd 755 hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4;
Skykon 3:c18342e4fddd 756 _2bx = sqrt(hx * hx + hy * hy);
Skykon 3:c18342e4fddd 757 _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4;
Skykon 3:c18342e4fddd 758 _4bx = 2.0f * _2bx;
Skykon 3:c18342e4fddd 759 _4bz = 2.0f * _2bz;
Skykon 3:c18342e4fddd 760
Skykon 3:c18342e4fddd 761 // Gradient decent algorithm corrective step
Skykon 3:c18342e4fddd 762 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);
Skykon 3:c18342e4fddd 763 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);
Skykon 3:c18342e4fddd 764 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);
Skykon 3:c18342e4fddd 765 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);
Skykon 3:c18342e4fddd 766 norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude
Skykon 3:c18342e4fddd 767 norm = 1.0f/norm;
Skykon 3:c18342e4fddd 768 s1 *= norm;
Skykon 3:c18342e4fddd 769 s2 *= norm;
Skykon 3:c18342e4fddd 770 s3 *= norm;
Skykon 3:c18342e4fddd 771 s4 *= norm;
Skykon 3:c18342e4fddd 772
Skykon 3:c18342e4fddd 773 // Compute rate of change of quaternion
Skykon 3:c18342e4fddd 774 qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1;
Skykon 3:c18342e4fddd 775 qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2;
Skykon 3:c18342e4fddd 776 qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3;
Skykon 3:c18342e4fddd 777 qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4;
Skykon 3:c18342e4fddd 778
Skykon 3:c18342e4fddd 779 // Integrate to yield quaternion
Skykon 3:c18342e4fddd 780 q1 += qDot1 * deltat;
Skykon 3:c18342e4fddd 781 q2 += qDot2 * deltat;
Skykon 3:c18342e4fddd 782 q3 += qDot3 * deltat;
Skykon 3:c18342e4fddd 783 q4 += qDot4 * deltat;
Skykon 3:c18342e4fddd 784 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion
Skykon 3:c18342e4fddd 785 norm = 1.0f/norm;
Skykon 3:c18342e4fddd 786 q[0] = q1 * norm;
Skykon 3:c18342e4fddd 787 q[1] = q2 * norm;
Skykon 3:c18342e4fddd 788 q[2] = q3 * norm;
Skykon 3:c18342e4fddd 789 q[3] = q4 * norm;
Skykon 3:c18342e4fddd 790
Skykon 3:c18342e4fddd 791 }
Skykon 3:c18342e4fddd 792
Skykon 3:c18342e4fddd 793 void MPU9250::MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
Skykon 3:c18342e4fddd 794 {
Skykon 3:c18342e4fddd 795 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability
Skykon 3:c18342e4fddd 796 float norm;
Skykon 3:c18342e4fddd 797 float hx, hy, bx, bz;
Skykon 3:c18342e4fddd 798 float vx, vy, vz, wx, wy, wz;
Skykon 3:c18342e4fddd 799 float ex, ey, ez;
Skykon 3:c18342e4fddd 800 float pa, pb, pc;
Skykon 3:c18342e4fddd 801
Skykon 3:c18342e4fddd 802 // Auxiliary variables to avoid repeated arithmetic
Skykon 3:c18342e4fddd 803 float q1q1 = q1 * q1;
Skykon 3:c18342e4fddd 804 float q1q2 = q1 * q2;
Skykon 3:c18342e4fddd 805 float q1q3 = q1 * q3;
Skykon 3:c18342e4fddd 806 float q1q4 = q1 * q4;
Skykon 3:c18342e4fddd 807 float q2q2 = q2 * q2;
Skykon 3:c18342e4fddd 808 float q2q3 = q2 * q3;
Skykon 3:c18342e4fddd 809 float q2q4 = q2 * q4;
Skykon 3:c18342e4fddd 810 float q3q3 = q3 * q3;
Skykon 3:c18342e4fddd 811 float q3q4 = q3 * q4;
Skykon 3:c18342e4fddd 812 float q4q4 = q4 * q4;
Skykon 3:c18342e4fddd 813
Skykon 3:c18342e4fddd 814 // Normalise accelerometer measurement
Skykon 3:c18342e4fddd 815 norm = sqrt(ax * ax + ay * ay + az * az);
Skykon 3:c18342e4fddd 816 if (norm == 0.0f) return; // handle NaN
Skykon 3:c18342e4fddd 817 norm = 1.0f / norm; // use reciprocal for division
Skykon 3:c18342e4fddd 818 ax *= norm;
Skykon 3:c18342e4fddd 819 ay *= norm;
Skykon 3:c18342e4fddd 820 az *= norm;
Skykon 3:c18342e4fddd 821
Skykon 3:c18342e4fddd 822 // Normalise magnetometer measurement
Skykon 3:c18342e4fddd 823 norm = sqrt(mx * mx + my * my + mz * mz);
Skykon 3:c18342e4fddd 824 if (norm == 0.0f) return; // handle NaN
Skykon 3:c18342e4fddd 825 norm = 1.0f / norm; // use reciprocal for division
Skykon 3:c18342e4fddd 826 mx *= norm;
Skykon 3:c18342e4fddd 827 my *= norm;
Skykon 3:c18342e4fddd 828 mz *= norm;
Skykon 3:c18342e4fddd 829
Skykon 3:c18342e4fddd 830 // Reference direction of Earth's magnetic field
Skykon 3:c18342e4fddd 831 hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3);
Skykon 3:c18342e4fddd 832 hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2);
Skykon 3:c18342e4fddd 833 bx = sqrt((hx * hx) + (hy * hy));
Skykon 3:c18342e4fddd 834 bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3);
Skykon 3:c18342e4fddd 835
Skykon 3:c18342e4fddd 836 // Estimated direction of gravity and magnetic field
Skykon 3:c18342e4fddd 837 vx = 2.0f * (q2q4 - q1q3);
Skykon 3:c18342e4fddd 838 vy = 2.0f * (q1q2 + q3q4);
Skykon 3:c18342e4fddd 839 vz = q1q1 - q2q2 - q3q3 + q4q4;
Skykon 3:c18342e4fddd 840 wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3);
Skykon 3:c18342e4fddd 841 wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4);
Skykon 3:c18342e4fddd 842 wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3);
Skykon 3:c18342e4fddd 843
Skykon 3:c18342e4fddd 844 // Error is cross product between estimated direction and measured direction of gravity
Skykon 3:c18342e4fddd 845 ex = (ay * vz - az * vy) + (my * wz - mz * wy);
Skykon 3:c18342e4fddd 846 ey = (az * vx - ax * vz) + (mz * wx - mx * wz);
Skykon 3:c18342e4fddd 847 ez = (ax * vy - ay * vx) + (mx * wy - my * wx);
Skykon 3:c18342e4fddd 848 if (Ki > 0.0f){
Skykon 3:c18342e4fddd 849 eInt[0] += ex; // accumulate integral error
Skykon 3:c18342e4fddd 850 eInt[1] += ey;
Skykon 3:c18342e4fddd 851 eInt[2] += ez;
Skykon 3:c18342e4fddd 852
Skykon 3:c18342e4fddd 853 }else{
Skykon 3:c18342e4fddd 854 eInt[0] = 0.0f; // prevent integral wind up
Skykon 3:c18342e4fddd 855 eInt[1] = 0.0f;
Skykon 3:c18342e4fddd 856 eInt[2] = 0.0f;
Skykon 3:c18342e4fddd 857 }
Skykon 3:c18342e4fddd 858
Skykon 3:c18342e4fddd 859 // Apply feedback terms
Skykon 3:c18342e4fddd 860 gx = gx + Kp * ex + Ki * eInt[0];
Skykon 3:c18342e4fddd 861 gy = gy + Kp * ey + Ki * eInt[1];
Skykon 3:c18342e4fddd 862 gz = gz + Kp * ez + Ki * eInt[2];
Skykon 3:c18342e4fddd 863
Skykon 3:c18342e4fddd 864 // Integrate rate of change of quaternion
Skykon 3:c18342e4fddd 865 pa = q2;
Skykon 3:c18342e4fddd 866 pb = q3;
Skykon 3:c18342e4fddd 867 pc = q4;
Skykon 3:c18342e4fddd 868 q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat);
Skykon 3:c18342e4fddd 869 q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat);
Skykon 3:c18342e4fddd 870 q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat);
Skykon 3:c18342e4fddd 871 q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat);
Skykon 3:c18342e4fddd 872
Skykon 3:c18342e4fddd 873 // Normalise quaternion
Skykon 3:c18342e4fddd 874 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);
Skykon 3:c18342e4fddd 875 norm = 1.0f / norm;
Skykon 3:c18342e4fddd 876 q[0] = q1 * norm;
Skykon 3:c18342e4fddd 877 q[1] = q2 * norm;
Skykon 3:c18342e4fddd 878 q[2] = q3 * norm;
Skykon 3:c18342e4fddd 879 q[3] = q4 * norm;
Skykon 3:c18342e4fddd 880
Skykon 3:c18342e4fddd 881 }
Skykon 3:c18342e4fddd 882
Skykon 3:c18342e4fddd 883 void MPU9250::translateQuaternionToDeg(float quaternion[4]){
Skykon 3:c18342e4fddd 884 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]);
Skykon 3:c18342e4fddd 885 roll = -asin(2.0f * (quaternion[1] * quaternion[3] - quaternion[0] * quaternion[2]));
Skykon 3:c18342e4fddd 886 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]);
Skykon 3:c18342e4fddd 887 }
Skykon 3:c18342e4fddd 888
Skykon 3:c18342e4fddd 889 void MPU9250::calibrateDegree(void){
Skykon 3:c18342e4fddd 890 pitch *= 180.0f / PI;
Skykon 3:c18342e4fddd 891 yaw *= 180.0f / PI;
Skykon 3:c18342e4fddd 892 yaw -= DECLINATION;
Skykon 3:c18342e4fddd 893 roll *= 180.0f / PI;
Skykon 3:c18342e4fddd 894 }
Skykon 3:c18342e4fddd 895
Skykon 3:c18342e4fddd 896 void MPU9250::transformCoordinateFromCompassToMPU(){
Skykon 3:c18342e4fddd 897 float buf = mx;
Skykon 3:c18342e4fddd 898 mx = my;
Skykon 3:c18342e4fddd 899 my = buf;
Skykon 3:c18342e4fddd 900 mz = -mz;
Skykon 3:c18342e4fddd 901 }