Library version of MPU9250AHRS code.

Fork of MPU9250AHRS by Janek Mann

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers AHRS.c Source File

AHRS.c

00001 #include "AHRS.h"
00002 #include "math.h"
00003 
00004 static float eInt[3] = {0.0f, 0.0f, 0.0f};
00005 
00006 // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays"
00007 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details)
00008 // which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute
00009 // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc.
00010 // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms
00011 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz!
00012 
00013 void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz, float deltat, float *q, float beta)
00014 {
00015     float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3];   // short name local variable for readability
00016     float norm;
00017     float hx, hy, _2bx, _2bz;
00018     float s1, s2, s3, s4;
00019     float qDot1, qDot2, qDot3, qDot4;
00020 
00021     // Auxiliary variables to avoid repeated arithmetic
00022     float _2q1mx;
00023     float _2q1my;
00024     float _2q1mz;
00025     float _2q2mx;
00026     float _4bx;
00027     float _4bz;
00028     float _2q1 = 2.0f * q1;
00029     float _2q2 = 2.0f * q2;
00030     float _2q3 = 2.0f * q3;
00031     float _2q4 = 2.0f * q4;
00032     float _2q1q3 = 2.0f * q1 * q3;
00033     float _2q3q4 = 2.0f * q3 * q4;
00034     float q1q1 = q1 * q1;
00035     float q1q2 = q1 * q2;
00036     float q1q3 = q1 * q3;
00037     float q1q4 = q1 * q4;
00038     float q2q2 = q2 * q2;
00039     float q2q3 = q2 * q3;
00040     float q2q4 = q2 * q4;
00041     float q3q3 = q3 * q3;
00042     float q3q4 = q3 * q4;
00043     float q4q4 = q4 * q4;
00044 
00045     // Normalise accelerometer measurement
00046     norm = sqrt(ax * ax + ay * ay + az * az);
00047     if (norm == 0.0f) return; // handle NaN
00048     norm = 1.0f/norm;
00049     ax *= norm;
00050     ay *= norm;
00051     az *= norm;
00052 
00053     // Normalise magnetometer measurement
00054     norm = sqrt(mx * mx + my * my + mz * mz);
00055     if (norm == 0.0f) return; // handle NaN
00056     norm = 1.0f/norm;
00057     mx *= norm;
00058     my *= norm;
00059     mz *= norm;
00060 
00061     // Reference direction of Earth's magnetic field
00062     _2q1mx = 2.0f * q1 * mx;
00063     _2q1my = 2.0f * q1 * my;
00064     _2q1mz = 2.0f * q1 * mz;
00065     _2q2mx = 2.0f * q2 * mx;
00066     hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4;
00067     hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4;
00068     _2bx = sqrt(hx * hx + hy * hy);
00069     _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4;
00070     _4bx = 2.0f * _2bx;
00071     _4bz = 2.0f * _2bz;
00072 
00073     // Gradient decent algorithm corrective step
00074     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);
00075     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);
00076     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);
00077     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);
00078     norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4);    // normalise step magnitude
00079     norm = 1.0f/norm;
00080     s1 *= norm;
00081     s2 *= norm;
00082     s3 *= norm;
00083     s4 *= norm;
00084 
00085     // Compute rate of change of quaternion
00086     qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1;
00087     qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2;
00088     qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3;
00089     qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4;
00090 
00091     // Integrate to yield quaternion
00092     q1 += qDot1 * deltat;
00093     q2 += qDot2 * deltat;
00094     q3 += qDot3 * deltat;
00095     q4 += qDot4 * deltat;
00096     norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);    // normalise quaternion
00097     norm = 1.0f/norm;
00098     q[0] = q1 * norm;
00099     q[1] = q2 * norm;
00100     q[2] = q3 * norm;
00101     q[3] = q4 * norm;
00102 
00103 }
00104 
00105 
00106 
00107 // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and
00108 // measured ones.
00109 void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz, float deltat, float *q)
00110 {
00111     float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3];   // short name local variable for readability
00112     float norm;
00113     float hx, hy, bx, bz;
00114     float vx, vy, vz, wx, wy, wz;
00115     float ex, ey, ez;
00116     float pa, pb, pc;
00117 
00118     // Auxiliary variables to avoid repeated arithmetic
00119     float q1q1 = q1 * q1;
00120     float q1q2 = q1 * q2;
00121     float q1q3 = q1 * q3;
00122     float q1q4 = q1 * q4;
00123     float q2q2 = q2 * q2;
00124     float q2q3 = q2 * q3;
00125     float q2q4 = q2 * q4;
00126     float q3q3 = q3 * q3;
00127     float q3q4 = q3 * q4;
00128     float q4q4 = q4 * q4;
00129 
00130     // Normalise accelerometer measurement
00131     norm = sqrt(ax * ax + ay * ay + az * az);
00132     if (norm == 0.0f) return; // handle NaN
00133     norm = 1.0f / norm;        // use reciprocal for division
00134     ax *= norm;
00135     ay *= norm;
00136     az *= norm;
00137 
00138     // Normalise magnetometer measurement
00139     norm = sqrt(mx * mx + my * my + mz * mz);
00140     if (norm == 0.0f) return; // handle NaN
00141     norm = 1.0f / norm;        // use reciprocal for division
00142     mx *= norm;
00143     my *= norm;
00144     mz *= norm;
00145 
00146     // Reference direction of Earth's magnetic field
00147     hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3);
00148     hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2);
00149     bx = sqrt((hx * hx) + (hy * hy));
00150     bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3);
00151 
00152     // Estimated direction of gravity and magnetic field
00153     vx = 2.0f * (q2q4 - q1q3);
00154     vy = 2.0f * (q1q2 + q3q4);
00155     vz = q1q1 - q2q2 - q3q3 + q4q4;
00156     wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3);
00157     wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4);
00158     wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3);
00159 
00160     // Error is cross product between estimated direction and measured direction of gravity
00161     ex = (ay * vz - az * vy) + (my * wz - mz * wy);
00162     ey = (az * vx - ax * vz) + (mz * wx - mx * wz);
00163     ez = (ax * vy - ay * vx) + (mx * wy - my * wx);
00164     if (Ki > 0.0f) {
00165         eInt[0] += ex;      // accumulate integral error
00166         eInt[1] += ey;
00167         eInt[2] += ez;
00168     } else {
00169         eInt[0] = 0.0f;     // prevent integral wind up
00170         eInt[1] = 0.0f;
00171         eInt[2] = 0.0f;
00172     }
00173 
00174     // Apply feedback terms
00175     gx = gx + Kp * ex + Ki * eInt[0];
00176     gy = gy + Kp * ey + Ki * eInt[1];
00177     gz = gz + Kp * ez + Ki * eInt[2];
00178 
00179     // Integrate rate of change of quaternion
00180     pa = q2;
00181     pb = q3;
00182     pc = q4;
00183     q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat);
00184     q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat);
00185     q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat);
00186     q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat);
00187 
00188     // Normalise quaternion
00189     norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);
00190     norm = 1.0f / norm;
00191     q[0] = q1 * norm;
00192     q[1] = q2 * norm;
00193     q[2] = q3 * norm;
00194     q[3] = q4 * norm;
00195 }