Library version of MPU9250AHRS code.
Fork of MPU9250AHRS by
AHRS.c@5:ea541d293095, 2014-09-08 (annotated)
- Committer:
- janekm
- Date:
- Mon Sep 08 21:50:33 2014 +0000
- Revision:
- 5:ea541d293095
- Parent:
- 4:404c35f32ce3
N/A
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
janekm | 4:404c35f32ce3 | 1 | #include "AHRS.h" |
janekm | 4:404c35f32ce3 | 2 | #include "math.h" |
janekm | 4:404c35f32ce3 | 3 | |
janekm | 5:ea541d293095 | 4 | static float eInt[3] = {0.0f, 0.0f, 0.0f}; |
janekm | 4:404c35f32ce3 | 5 | |
janekm | 4:404c35f32ce3 | 6 | // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" |
janekm | 4:404c35f32ce3 | 7 | // (see http://www.x-io.co.uk/category/open-source/ for examples and more details) |
janekm | 4:404c35f32ce3 | 8 | // which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute |
janekm | 4:404c35f32ce3 | 9 | // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc. |
janekm | 4:404c35f32ce3 | 10 | // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms |
janekm | 4:404c35f32ce3 | 11 | // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz! |
janekm | 4:404c35f32ce3 | 12 | |
janekm | 5:ea541d293095 | 13 | 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) |
janekm | 5:ea541d293095 | 14 | { |
janekm | 5:ea541d293095 | 15 | float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability |
janekm | 5:ea541d293095 | 16 | float norm; |
janekm | 5:ea541d293095 | 17 | float hx, hy, _2bx, _2bz; |
janekm | 5:ea541d293095 | 18 | float s1, s2, s3, s4; |
janekm | 5:ea541d293095 | 19 | float qDot1, qDot2, qDot3, qDot4; |
janekm | 4:404c35f32ce3 | 20 | |
janekm | 5:ea541d293095 | 21 | // Auxiliary variables to avoid repeated arithmetic |
janekm | 5:ea541d293095 | 22 | float _2q1mx; |
janekm | 5:ea541d293095 | 23 | float _2q1my; |
janekm | 5:ea541d293095 | 24 | float _2q1mz; |
janekm | 5:ea541d293095 | 25 | float _2q2mx; |
janekm | 5:ea541d293095 | 26 | float _4bx; |
janekm | 5:ea541d293095 | 27 | float _4bz; |
janekm | 5:ea541d293095 | 28 | float _2q1 = 2.0f * q1; |
janekm | 5:ea541d293095 | 29 | float _2q2 = 2.0f * q2; |
janekm | 5:ea541d293095 | 30 | float _2q3 = 2.0f * q3; |
janekm | 5:ea541d293095 | 31 | float _2q4 = 2.0f * q4; |
janekm | 5:ea541d293095 | 32 | float _2q1q3 = 2.0f * q1 * q3; |
janekm | 5:ea541d293095 | 33 | float _2q3q4 = 2.0f * q3 * q4; |
janekm | 5:ea541d293095 | 34 | float q1q1 = q1 * q1; |
janekm | 5:ea541d293095 | 35 | float q1q2 = q1 * q2; |
janekm | 5:ea541d293095 | 36 | float q1q3 = q1 * q3; |
janekm | 5:ea541d293095 | 37 | float q1q4 = q1 * q4; |
janekm | 5:ea541d293095 | 38 | float q2q2 = q2 * q2; |
janekm | 5:ea541d293095 | 39 | float q2q3 = q2 * q3; |
janekm | 5:ea541d293095 | 40 | float q2q4 = q2 * q4; |
janekm | 5:ea541d293095 | 41 | float q3q3 = q3 * q3; |
janekm | 5:ea541d293095 | 42 | float q3q4 = q3 * q4; |
janekm | 5:ea541d293095 | 43 | float q4q4 = q4 * q4; |
janekm | 4:404c35f32ce3 | 44 | |
janekm | 5:ea541d293095 | 45 | // Normalise accelerometer measurement |
janekm | 5:ea541d293095 | 46 | norm = sqrt(ax * ax + ay * ay + az * az); |
janekm | 5:ea541d293095 | 47 | if (norm == 0.0f) return; // handle NaN |
janekm | 5:ea541d293095 | 48 | norm = 1.0f/norm; |
janekm | 5:ea541d293095 | 49 | ax *= norm; |
janekm | 5:ea541d293095 | 50 | ay *= norm; |
janekm | 5:ea541d293095 | 51 | az *= norm; |
janekm | 4:404c35f32ce3 | 52 | |
janekm | 5:ea541d293095 | 53 | // Normalise magnetometer measurement |
janekm | 5:ea541d293095 | 54 | norm = sqrt(mx * mx + my * my + mz * mz); |
janekm | 5:ea541d293095 | 55 | if (norm == 0.0f) return; // handle NaN |
janekm | 5:ea541d293095 | 56 | norm = 1.0f/norm; |
janekm | 5:ea541d293095 | 57 | mx *= norm; |
janekm | 5:ea541d293095 | 58 | my *= norm; |
janekm | 5:ea541d293095 | 59 | mz *= norm; |
janekm | 4:404c35f32ce3 | 60 | |
janekm | 5:ea541d293095 | 61 | // Reference direction of Earth's magnetic field |
janekm | 5:ea541d293095 | 62 | _2q1mx = 2.0f * q1 * mx; |
janekm | 5:ea541d293095 | 63 | _2q1my = 2.0f * q1 * my; |
janekm | 5:ea541d293095 | 64 | _2q1mz = 2.0f * q1 * mz; |
janekm | 5:ea541d293095 | 65 | _2q2mx = 2.0f * q2 * mx; |
janekm | 5:ea541d293095 | 66 | hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4; |
janekm | 5:ea541d293095 | 67 | hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4; |
janekm | 5:ea541d293095 | 68 | _2bx = sqrt(hx * hx + hy * hy); |
janekm | 5:ea541d293095 | 69 | _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4; |
janekm | 5:ea541d293095 | 70 | _4bx = 2.0f * _2bx; |
janekm | 5:ea541d293095 | 71 | _4bz = 2.0f * _2bz; |
janekm | 4:404c35f32ce3 | 72 | |
janekm | 5:ea541d293095 | 73 | // Gradient decent algorithm corrective step |
janekm | 5:ea541d293095 | 74 | 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); |
janekm | 5:ea541d293095 | 75 | 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); |
janekm | 5:ea541d293095 | 76 | 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); |
janekm | 5:ea541d293095 | 77 | 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); |
janekm | 5:ea541d293095 | 78 | norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude |
janekm | 5:ea541d293095 | 79 | norm = 1.0f/norm; |
janekm | 5:ea541d293095 | 80 | s1 *= norm; |
janekm | 5:ea541d293095 | 81 | s2 *= norm; |
janekm | 5:ea541d293095 | 82 | s3 *= norm; |
janekm | 5:ea541d293095 | 83 | s4 *= norm; |
janekm | 4:404c35f32ce3 | 84 | |
janekm | 5:ea541d293095 | 85 | // Compute rate of change of quaternion |
janekm | 5:ea541d293095 | 86 | qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1; |
janekm | 5:ea541d293095 | 87 | qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2; |
janekm | 5:ea541d293095 | 88 | qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3; |
janekm | 5:ea541d293095 | 89 | qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4; |
janekm | 4:404c35f32ce3 | 90 | |
janekm | 5:ea541d293095 | 91 | // Integrate to yield quaternion |
janekm | 5:ea541d293095 | 92 | q1 += qDot1 * deltat; |
janekm | 5:ea541d293095 | 93 | q2 += qDot2 * deltat; |
janekm | 5:ea541d293095 | 94 | q3 += qDot3 * deltat; |
janekm | 5:ea541d293095 | 95 | q4 += qDot4 * deltat; |
janekm | 5:ea541d293095 | 96 | norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion |
janekm | 5:ea541d293095 | 97 | norm = 1.0f/norm; |
janekm | 5:ea541d293095 | 98 | q[0] = q1 * norm; |
janekm | 5:ea541d293095 | 99 | q[1] = q2 * norm; |
janekm | 5:ea541d293095 | 100 | q[2] = q3 * norm; |
janekm | 5:ea541d293095 | 101 | q[3] = q4 * norm; |
janekm | 4:404c35f32ce3 | 102 | |
janekm | 4:404c35f32ce3 | 103 | } |
janekm | 4:404c35f32ce3 | 104 | |
janekm | 4:404c35f32ce3 | 105 | |
janekm | 4:404c35f32ce3 | 106 | |
janekm | 4:404c35f32ce3 | 107 | // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and |
janekm | 4:404c35f32ce3 | 108 | // measured ones. |
janekm | 5:ea541d293095 | 109 | void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz, float deltat, float *q) |
janekm | 5:ea541d293095 | 110 | { |
janekm | 5:ea541d293095 | 111 | float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability |
janekm | 5:ea541d293095 | 112 | float norm; |
janekm | 5:ea541d293095 | 113 | float hx, hy, bx, bz; |
janekm | 5:ea541d293095 | 114 | float vx, vy, vz, wx, wy, wz; |
janekm | 5:ea541d293095 | 115 | float ex, ey, ez; |
janekm | 5:ea541d293095 | 116 | float pa, pb, pc; |
janekm | 4:404c35f32ce3 | 117 | |
janekm | 5:ea541d293095 | 118 | // Auxiliary variables to avoid repeated arithmetic |
janekm | 5:ea541d293095 | 119 | float q1q1 = q1 * q1; |
janekm | 5:ea541d293095 | 120 | float q1q2 = q1 * q2; |
janekm | 5:ea541d293095 | 121 | float q1q3 = q1 * q3; |
janekm | 5:ea541d293095 | 122 | float q1q4 = q1 * q4; |
janekm | 5:ea541d293095 | 123 | float q2q2 = q2 * q2; |
janekm | 5:ea541d293095 | 124 | float q2q3 = q2 * q3; |
janekm | 5:ea541d293095 | 125 | float q2q4 = q2 * q4; |
janekm | 5:ea541d293095 | 126 | float q3q3 = q3 * q3; |
janekm | 5:ea541d293095 | 127 | float q3q4 = q3 * q4; |
janekm | 5:ea541d293095 | 128 | float q4q4 = q4 * q4; |
janekm | 4:404c35f32ce3 | 129 | |
janekm | 5:ea541d293095 | 130 | // Normalise accelerometer measurement |
janekm | 5:ea541d293095 | 131 | norm = sqrt(ax * ax + ay * ay + az * az); |
janekm | 5:ea541d293095 | 132 | if (norm == 0.0f) return; // handle NaN |
janekm | 5:ea541d293095 | 133 | norm = 1.0f / norm; // use reciprocal for division |
janekm | 5:ea541d293095 | 134 | ax *= norm; |
janekm | 5:ea541d293095 | 135 | ay *= norm; |
janekm | 5:ea541d293095 | 136 | az *= norm; |
janekm | 4:404c35f32ce3 | 137 | |
janekm | 5:ea541d293095 | 138 | // Normalise magnetometer measurement |
janekm | 5:ea541d293095 | 139 | norm = sqrt(mx * mx + my * my + mz * mz); |
janekm | 5:ea541d293095 | 140 | if (norm == 0.0f) return; // handle NaN |
janekm | 5:ea541d293095 | 141 | norm = 1.0f / norm; // use reciprocal for division |
janekm | 5:ea541d293095 | 142 | mx *= norm; |
janekm | 5:ea541d293095 | 143 | my *= norm; |
janekm | 5:ea541d293095 | 144 | mz *= norm; |
janekm | 4:404c35f32ce3 | 145 | |
janekm | 5:ea541d293095 | 146 | // Reference direction of Earth's magnetic field |
janekm | 5:ea541d293095 | 147 | hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3); |
janekm | 5:ea541d293095 | 148 | hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2); |
janekm | 5:ea541d293095 | 149 | bx = sqrt((hx * hx) + (hy * hy)); |
janekm | 5:ea541d293095 | 150 | bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3); |
janekm | 4:404c35f32ce3 | 151 | |
janekm | 5:ea541d293095 | 152 | // Estimated direction of gravity and magnetic field |
janekm | 5:ea541d293095 | 153 | vx = 2.0f * (q2q4 - q1q3); |
janekm | 5:ea541d293095 | 154 | vy = 2.0f * (q1q2 + q3q4); |
janekm | 5:ea541d293095 | 155 | vz = q1q1 - q2q2 - q3q3 + q4q4; |
janekm | 5:ea541d293095 | 156 | wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3); |
janekm | 5:ea541d293095 | 157 | wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4); |
janekm | 5:ea541d293095 | 158 | wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3); |
janekm | 4:404c35f32ce3 | 159 | |
janekm | 5:ea541d293095 | 160 | // Error is cross product between estimated direction and measured direction of gravity |
janekm | 5:ea541d293095 | 161 | ex = (ay * vz - az * vy) + (my * wz - mz * wy); |
janekm | 5:ea541d293095 | 162 | ey = (az * vx - ax * vz) + (mz * wx - mx * wz); |
janekm | 5:ea541d293095 | 163 | ez = (ax * vy - ay * vx) + (mx * wy - my * wx); |
janekm | 5:ea541d293095 | 164 | if (Ki > 0.0f) { |
janekm | 5:ea541d293095 | 165 | eInt[0] += ex; // accumulate integral error |
janekm | 5:ea541d293095 | 166 | eInt[1] += ey; |
janekm | 5:ea541d293095 | 167 | eInt[2] += ez; |
janekm | 5:ea541d293095 | 168 | } else { |
janekm | 5:ea541d293095 | 169 | eInt[0] = 0.0f; // prevent integral wind up |
janekm | 5:ea541d293095 | 170 | eInt[1] = 0.0f; |
janekm | 5:ea541d293095 | 171 | eInt[2] = 0.0f; |
janekm | 5:ea541d293095 | 172 | } |
janekm | 4:404c35f32ce3 | 173 | |
janekm | 5:ea541d293095 | 174 | // Apply feedback terms |
janekm | 5:ea541d293095 | 175 | gx = gx + Kp * ex + Ki * eInt[0]; |
janekm | 5:ea541d293095 | 176 | gy = gy + Kp * ey + Ki * eInt[1]; |
janekm | 5:ea541d293095 | 177 | gz = gz + Kp * ez + Ki * eInt[2]; |
janekm | 4:404c35f32ce3 | 178 | |
janekm | 5:ea541d293095 | 179 | // Integrate rate of change of quaternion |
janekm | 5:ea541d293095 | 180 | pa = q2; |
janekm | 5:ea541d293095 | 181 | pb = q3; |
janekm | 5:ea541d293095 | 182 | pc = q4; |
janekm | 5:ea541d293095 | 183 | q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat); |
janekm | 5:ea541d293095 | 184 | q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat); |
janekm | 5:ea541d293095 | 185 | q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat); |
janekm | 5:ea541d293095 | 186 | q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat); |
janekm | 4:404c35f32ce3 | 187 | |
janekm | 5:ea541d293095 | 188 | // Normalise quaternion |
janekm | 5:ea541d293095 | 189 | norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); |
janekm | 5:ea541d293095 | 190 | norm = 1.0f / norm; |
janekm | 5:ea541d293095 | 191 | q[0] = q1 * norm; |
janekm | 5:ea541d293095 | 192 | q[1] = q2 * norm; |
janekm | 5:ea541d293095 | 193 | q[2] = q3 * norm; |
janekm | 5:ea541d293095 | 194 | q[3] = q4 * norm; |
janekm | 5:ea541d293095 | 195 | } |