├── MadgwickAHRS ├── MadgwickAHRS.c └── MadgwickAHRS.h └── MahonyAHRS ├── MahonyAHRS.c └── MahonyAHRS.h /MadgwickAHRS/MadgwickAHRS.c: -------------------------------------------------------------------------------- 1 | //===================================================================================================== 2 | // MadgwickAHRS.c 3 | //===================================================================================================== 4 | // 5 | // Implementation of Madgwick's IMU and AHRS algorithms. 6 | // See: http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms 7 | // 8 | // Date Author Notes 9 | // 29/09/2011 SOH Madgwick Initial release 10 | // 02/10/2011 SOH Madgwick Optimised for reduced CPU load 11 | // 19/02/2012 SOH Madgwick Magnetometer measurement is normalised 12 | // 13 | //===================================================================================================== 14 | 15 | //--------------------------------------------------------------------------------------------------- 16 | // Header files 17 | 18 | #include "MadgwickAHRS.h" 19 | #include 20 | 21 | //--------------------------------------------------------------------------------------------------- 22 | // Definitions 23 | 24 | #define sampleFreq 512.0f // sample frequency in Hz 25 | #define betaDef 0.1f // 2 * proportional gain 26 | 27 | //--------------------------------------------------------------------------------------------------- 28 | // Variable definitions 29 | 30 | volatile float beta = betaDef; // 2 * proportional gain (Kp) 31 | volatile float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to auxiliary frame 32 | 33 | //--------------------------------------------------------------------------------------------------- 34 | // Function declarations 35 | 36 | float invSqrt(float x); 37 | 38 | //==================================================================================================== 39 | // Functions 40 | 41 | //--------------------------------------------------------------------------------------------------- 42 | // AHRS algorithm update 43 | 44 | void MadgwickAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz) { 45 | float recipNorm; 46 | float s0, s1, s2, s3; 47 | float qDot1, qDot2, qDot3, qDot4; 48 | float hx, hy; 49 | float _2q0mx, _2q0my, _2q0mz, _2q1mx, _2bx, _2bz, _4bx, _4bz, _2q0, _2q1, _2q2, _2q3, _2q0q2, _2q2q3, q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; 50 | 51 | // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation) 52 | if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { 53 | MadgwickAHRSupdateIMU(gx, gy, gz, ax, ay, az); 54 | return; 55 | } 56 | 57 | // Rate of change of quaternion from gyroscope 58 | qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); 59 | qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); 60 | qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); 61 | qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); 62 | 63 | // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) 64 | if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { 65 | 66 | // Normalise accelerometer measurement 67 | recipNorm = invSqrt(ax * ax + ay * ay + az * az); 68 | ax *= recipNorm; 69 | ay *= recipNorm; 70 | az *= recipNorm; 71 | 72 | // Normalise magnetometer measurement 73 | recipNorm = invSqrt(mx * mx + my * my + mz * mz); 74 | mx *= recipNorm; 75 | my *= recipNorm; 76 | mz *= recipNorm; 77 | 78 | // Auxiliary variables to avoid repeated arithmetic 79 | _2q0mx = 2.0f * q0 * mx; 80 | _2q0my = 2.0f * q0 * my; 81 | _2q0mz = 2.0f * q0 * mz; 82 | _2q1mx = 2.0f * q1 * mx; 83 | _2q0 = 2.0f * q0; 84 | _2q1 = 2.0f * q1; 85 | _2q2 = 2.0f * q2; 86 | _2q3 = 2.0f * q3; 87 | _2q0q2 = 2.0f * q0 * q2; 88 | _2q2q3 = 2.0f * q2 * q3; 89 | q0q0 = q0 * q0; 90 | q0q1 = q0 * q1; 91 | q0q2 = q0 * q2; 92 | q0q3 = q0 * q3; 93 | q1q1 = q1 * q1; 94 | q1q2 = q1 * q2; 95 | q1q3 = q1 * q3; 96 | q2q2 = q2 * q2; 97 | q2q3 = q2 * q3; 98 | q3q3 = q3 * q3; 99 | 100 | // Reference direction of Earth's magnetic field 101 | hx = mx * q0q0 - _2q0my * q3 + _2q0mz * q2 + mx * q1q1 + _2q1 * my * q2 + _2q1 * mz * q3 - mx * q2q2 - mx * q3q3; 102 | hy = _2q0mx * q3 + my * q0q0 - _2q0mz * q1 + _2q1mx * q2 - my * q1q1 + my * q2q2 + _2q2 * mz * q3 - my * q3q3; 103 | _2bx = sqrt(hx * hx + hy * hy); 104 | _2bz = -_2q0mx * q2 + _2q0my * q1 + mz * q0q0 + _2q1mx * q3 - mz * q1q1 + _2q2 * my * q3 - mz * q2q2 + mz * q3q3; 105 | _4bx = 2.0f * _2bx; 106 | _4bz = 2.0f * _2bz; 107 | 108 | // Gradient decent algorithm corrective step 109 | s0 = -_2q2 * (2.0f * q1q3 - _2q0q2 - ax) + _2q1 * (2.0f * q0q1 + _2q2q3 - ay) - _2bz * q2 * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (-_2bx * q3 + _2bz * q1) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + _2bx * q2 * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); 110 | s1 = _2q3 * (2.0f * q1q3 - _2q0q2 - ax) + _2q0 * (2.0f * q0q1 + _2q2q3 - ay) - 4.0f * q1 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + _2bz * q3 * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (_2bx * q2 + _2bz * q0) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + (_2bx * q3 - _4bz * q1) * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); 111 | s2 = -_2q0 * (2.0f * q1q3 - _2q0q2 - ax) + _2q3 * (2.0f * q0q1 + _2q2q3 - ay) - 4.0f * q2 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + (-_4bx * q2 - _2bz * q0) * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (_2bx * q1 + _2bz * q3) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + (_2bx * q0 - _4bz * q2) * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); 112 | s3 = _2q1 * (2.0f * q1q3 - _2q0q2 - ax) + _2q2 * (2.0f * q0q1 + _2q2q3 - ay) + (-_4bx * q3 + _2bz * q1) * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (-_2bx * q0 + _2bz * q2) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + _2bx * q1 * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); 113 | recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude 114 | s0 *= recipNorm; 115 | s1 *= recipNorm; 116 | s2 *= recipNorm; 117 | s3 *= recipNorm; 118 | 119 | // Apply feedback step 120 | qDot1 -= beta * s0; 121 | qDot2 -= beta * s1; 122 | qDot3 -= beta * s2; 123 | qDot4 -= beta * s3; 124 | } 125 | 126 | // Integrate rate of change of quaternion to yield quaternion 127 | q0 += qDot1 * (1.0f / sampleFreq); 128 | q1 += qDot2 * (1.0f / sampleFreq); 129 | q2 += qDot3 * (1.0f / sampleFreq); 130 | q3 += qDot4 * (1.0f / sampleFreq); 131 | 132 | // Normalise quaternion 133 | recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); 134 | q0 *= recipNorm; 135 | q1 *= recipNorm; 136 | q2 *= recipNorm; 137 | q3 *= recipNorm; 138 | } 139 | 140 | //--------------------------------------------------------------------------------------------------- 141 | // IMU algorithm update 142 | 143 | void MadgwickAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az) { 144 | float recipNorm; 145 | float s0, s1, s2, s3; 146 | float qDot1, qDot2, qDot3, qDot4; 147 | float _2q0, _2q1, _2q2, _2q3, _4q0, _4q1, _4q2 ,_8q1, _8q2, q0q0, q1q1, q2q2, q3q3; 148 | 149 | // Rate of change of quaternion from gyroscope 150 | qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); 151 | qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); 152 | qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); 153 | qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); 154 | 155 | // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) 156 | if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { 157 | 158 | // Normalise accelerometer measurement 159 | recipNorm = invSqrt(ax * ax + ay * ay + az * az); 160 | ax *= recipNorm; 161 | ay *= recipNorm; 162 | az *= recipNorm; 163 | 164 | // Auxiliary variables to avoid repeated arithmetic 165 | _2q0 = 2.0f * q0; 166 | _2q1 = 2.0f * q1; 167 | _2q2 = 2.0f * q2; 168 | _2q3 = 2.0f * q3; 169 | _4q0 = 4.0f * q0; 170 | _4q1 = 4.0f * q1; 171 | _4q2 = 4.0f * q2; 172 | _8q1 = 8.0f * q1; 173 | _8q2 = 8.0f * q2; 174 | q0q0 = q0 * q0; 175 | q1q1 = q1 * q1; 176 | q2q2 = q2 * q2; 177 | q3q3 = q3 * q3; 178 | 179 | // Gradient decent algorithm corrective step 180 | s0 = _4q0 * q2q2 + _2q2 * ax + _4q0 * q1q1 - _2q1 * ay; 181 | s1 = _4q1 * q3q3 - _2q3 * ax + 4.0f * q0q0 * q1 - _2q0 * ay - _4q1 + _8q1 * q1q1 + _8q1 * q2q2 + _4q1 * az; 182 | s2 = 4.0f * q0q0 * q2 + _2q0 * ax + _4q2 * q3q3 - _2q3 * ay - _4q2 + _8q2 * q1q1 + _8q2 * q2q2 + _4q2 * az; 183 | s3 = 4.0f * q1q1 * q3 - _2q1 * ax + 4.0f * q2q2 * q3 - _2q2 * ay; 184 | recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude 185 | s0 *= recipNorm; 186 | s1 *= recipNorm; 187 | s2 *= recipNorm; 188 | s3 *= recipNorm; 189 | 190 | // Apply feedback step 191 | qDot1 -= beta * s0; 192 | qDot2 -= beta * s1; 193 | qDot3 -= beta * s2; 194 | qDot4 -= beta * s3; 195 | } 196 | 197 | // Integrate rate of change of quaternion to yield quaternion 198 | q0 += qDot1 * (1.0f / sampleFreq); 199 | q1 += qDot2 * (1.0f / sampleFreq); 200 | q2 += qDot3 * (1.0f / sampleFreq); 201 | q3 += qDot4 * (1.0f / sampleFreq); 202 | 203 | // Normalise quaternion 204 | recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); 205 | q0 *= recipNorm; 206 | q1 *= recipNorm; 207 | q2 *= recipNorm; 208 | q3 *= recipNorm; 209 | } 210 | 211 | 212 | int instability_fix = 1; 213 | 214 | //--------------------------------------------------------------------------------------------------- 215 | // Fast inverse square-root 216 | // See: http://en.wikipedia.org/wiki/Fast_inverse_square_root 217 | 218 | float invSqrt(float x) { 219 | if (instability_fix == 0) 220 | { 221 | /* original code */ 222 | float halfx = 0.5f * x; 223 | float y = x; 224 | long i = *(long*)&y; 225 | i = 0x5f3759df - (i>>1); 226 | y = *(float*)&i; 227 | y = y * (1.5f - (halfx * y * y)); 228 | return y; 229 | } 230 | else if (instability_fix == 1) 231 | { 232 | /* close-to-optimal method with low cost from http://pizer.wordpress.com/2008/10/12/fast-inverse-square-root */ 233 | unsigned int i = 0x5F1F1412 - (*(unsigned int*)&x >> 1); 234 | float tmp = *(float*)&i; 235 | return tmp * (1.69000231f - 0.714158168f * x * tmp * tmp); 236 | } 237 | else 238 | { 239 | /* optimal but expensive method: */ 240 | return 1.0f / sqrtf(x); 241 | } 242 | } 243 | 244 | //==================================================================================================== 245 | // END OF CODE 246 | //==================================================================================================== 247 | -------------------------------------------------------------------------------- /MadgwickAHRS/MadgwickAHRS.h: -------------------------------------------------------------------------------- 1 | //===================================================================================================== 2 | // MadgwickAHRS.h 3 | //===================================================================================================== 4 | // 5 | // Implementation of Madgwick's IMU and AHRS algorithms. 6 | // See: http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms 7 | // 8 | // Date Author Notes 9 | // 29/09/2011 SOH Madgwick Initial release 10 | // 02/10/2011 SOH Madgwick Optimised for reduced CPU load 11 | // 12 | //===================================================================================================== 13 | #ifndef MadgwickAHRS_h 14 | #define MadgwickAHRS_h 15 | 16 | //---------------------------------------------------------------------------------------------------- 17 | // Variable declaration 18 | 19 | extern volatile float beta; // algorithm gain 20 | extern volatile float q0, q1, q2, q3; // quaternion of sensor frame relative to auxiliary frame 21 | 22 | //--------------------------------------------------------------------------------------------------- 23 | // Function declarations 24 | 25 | void MadgwickAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz); 26 | void MadgwickAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az); 27 | 28 | #endif 29 | //===================================================================================================== 30 | // End of file 31 | //===================================================================================================== 32 | -------------------------------------------------------------------------------- /MahonyAHRS/MahonyAHRS.c: -------------------------------------------------------------------------------- 1 | //===================================================================================================== 2 | // MahonyAHRS.c 3 | //===================================================================================================== 4 | // 5 | // Madgwick's implementation of Mayhony's AHRS algorithm. 6 | // See: http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms 7 | // 8 | // Date Author Notes 9 | // 29/09/2011 SOH Madgwick Initial release 10 | // 02/10/2011 SOH Madgwick Optimised for reduced CPU load 11 | // 12 | //===================================================================================================== 13 | 14 | //--------------------------------------------------------------------------------------------------- 15 | // Header files 16 | 17 | #include "MahonyAHRS.h" 18 | #include 19 | 20 | //--------------------------------------------------------------------------------------------------- 21 | // Definitions 22 | 23 | #define sampleFreq 512.0f // sample frequency in Hz 24 | #define twoKpDef (2.0f * 0.5f) // 2 * proportional gain 25 | #define twoKiDef (2.0f * 0.0f) // 2 * integral gain 26 | 27 | //--------------------------------------------------------------------------------------------------- 28 | // Variable definitions 29 | 30 | volatile float twoKp = twoKpDef; // 2 * proportional gain (Kp) 31 | volatile float twoKi = twoKiDef; // 2 * integral gain (Ki) 32 | volatile float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to auxiliary frame 33 | volatile float integralFBx = 0.0f, integralFBy = 0.0f, integralFBz = 0.0f; // integral error terms scaled by Ki 34 | 35 | //--------------------------------------------------------------------------------------------------- 36 | // Function declarations 37 | 38 | float invSqrt(float x); 39 | 40 | //==================================================================================================== 41 | // Functions 42 | 43 | //--------------------------------------------------------------------------------------------------- 44 | // AHRS algorithm update 45 | 46 | void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz) { 47 | float recipNorm; 48 | float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; 49 | float hx, hy, bx, bz; 50 | float halfvx, halfvy, halfvz, halfwx, halfwy, halfwz; 51 | float halfex, halfey, halfez; 52 | float qa, qb, qc; 53 | 54 | // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation) 55 | if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { 56 | MahonyAHRSupdateIMU(gx, gy, gz, ax, ay, az); 57 | return; 58 | } 59 | 60 | // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) 61 | if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { 62 | 63 | // Normalise accelerometer measurement 64 | recipNorm = invSqrt(ax * ax + ay * ay + az * az); 65 | ax *= recipNorm; 66 | ay *= recipNorm; 67 | az *= recipNorm; 68 | 69 | // Normalise magnetometer measurement 70 | recipNorm = invSqrt(mx * mx + my * my + mz * mz); 71 | mx *= recipNorm; 72 | my *= recipNorm; 73 | mz *= recipNorm; 74 | 75 | // Auxiliary variables to avoid repeated arithmetic 76 | q0q0 = q0 * q0; 77 | q0q1 = q0 * q1; 78 | q0q2 = q0 * q2; 79 | q0q3 = q0 * q3; 80 | q1q1 = q1 * q1; 81 | q1q2 = q1 * q2; 82 | q1q3 = q1 * q3; 83 | q2q2 = q2 * q2; 84 | q2q3 = q2 * q3; 85 | q3q3 = q3 * q3; 86 | 87 | // Reference direction of Earth's magnetic field 88 | hx = 2.0f * (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2)); 89 | hy = 2.0f * (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1)); 90 | bx = sqrt(hx * hx + hy * hy); 91 | bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2)); 92 | 93 | // Estimated direction of gravity and magnetic field 94 | halfvx = q1q3 - q0q2; 95 | halfvy = q0q1 + q2q3; 96 | halfvz = q0q0 - 0.5f + q3q3; 97 | halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2); 98 | halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3); 99 | halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2); 100 | 101 | // Error is sum of cross product between estimated direction and measured direction of field vectors 102 | halfex = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy); 103 | halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz); 104 | halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx); 105 | 106 | // Compute and apply integral feedback if enabled 107 | if(twoKi > 0.0f) { 108 | integralFBx += twoKi * halfex * (1.0f / sampleFreq); // integral error scaled by Ki 109 | integralFBy += twoKi * halfey * (1.0f / sampleFreq); 110 | integralFBz += twoKi * halfez * (1.0f / sampleFreq); 111 | gx += integralFBx; // apply integral feedback 112 | gy += integralFBy; 113 | gz += integralFBz; 114 | } 115 | else { 116 | integralFBx = 0.0f; // prevent integral windup 117 | integralFBy = 0.0f; 118 | integralFBz = 0.0f; 119 | } 120 | 121 | // Apply proportional feedback 122 | gx += twoKp * halfex; 123 | gy += twoKp * halfey; 124 | gz += twoKp * halfez; 125 | } 126 | 127 | // Integrate rate of change of quaternion 128 | gx *= (0.5f * (1.0f / sampleFreq)); // pre-multiply common factors 129 | gy *= (0.5f * (1.0f / sampleFreq)); 130 | gz *= (0.5f * (1.0f / sampleFreq)); 131 | qa = q0; 132 | qb = q1; 133 | qc = q2; 134 | q0 += (-qb * gx - qc * gy - q3 * gz); 135 | q1 += (qa * gx + qc * gz - q3 * gy); 136 | q2 += (qa * gy - qb * gz + q3 * gx); 137 | q3 += (qa * gz + qb * gy - qc * gx); 138 | 139 | // Normalise quaternion 140 | recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); 141 | q0 *= recipNorm; 142 | q1 *= recipNorm; 143 | q2 *= recipNorm; 144 | q3 *= recipNorm; 145 | } 146 | 147 | //--------------------------------------------------------------------------------------------------- 148 | // IMU algorithm update 149 | 150 | void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az) { 151 | float recipNorm; 152 | float halfvx, halfvy, halfvz; 153 | float halfex, halfey, halfez; 154 | float qa, qb, qc; 155 | 156 | // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) 157 | if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { 158 | 159 | // Normalise accelerometer measurement 160 | recipNorm = invSqrt(ax * ax + ay * ay + az * az); 161 | ax *= recipNorm; 162 | ay *= recipNorm; 163 | az *= recipNorm; 164 | 165 | // Estimated direction of gravity and vector perpendicular to magnetic flux 166 | halfvx = q1 * q3 - q0 * q2; 167 | halfvy = q0 * q1 + q2 * q3; 168 | halfvz = q0 * q0 - 0.5f + q3 * q3; 169 | 170 | // Error is sum of cross product between estimated and measured direction of gravity 171 | halfex = (ay * halfvz - az * halfvy); 172 | halfey = (az * halfvx - ax * halfvz); 173 | halfez = (ax * halfvy - ay * halfvx); 174 | 175 | // Compute and apply integral feedback if enabled 176 | if(twoKi > 0.0f) { 177 | integralFBx += twoKi * halfex * (1.0f / sampleFreq); // integral error scaled by Ki 178 | integralFBy += twoKi * halfey * (1.0f / sampleFreq); 179 | integralFBz += twoKi * halfez * (1.0f / sampleFreq); 180 | gx += integralFBx; // apply integral feedback 181 | gy += integralFBy; 182 | gz += integralFBz; 183 | } 184 | else { 185 | integralFBx = 0.0f; // prevent integral windup 186 | integralFBy = 0.0f; 187 | integralFBz = 0.0f; 188 | } 189 | 190 | // Apply proportional feedback 191 | gx += twoKp * halfex; 192 | gy += twoKp * halfey; 193 | gz += twoKp * halfez; 194 | } 195 | 196 | // Integrate rate of change of quaternion 197 | gx *= (0.5f * (1.0f / sampleFreq)); // pre-multiply common factors 198 | gy *= (0.5f * (1.0f / sampleFreq)); 199 | gz *= (0.5f * (1.0f / sampleFreq)); 200 | qa = q0; 201 | qb = q1; 202 | qc = q2; 203 | q0 += (-qb * gx - qc * gy - q3 * gz); 204 | q1 += (qa * gx + qc * gz - q3 * gy); 205 | q2 += (qa * gy - qb * gz + q3 * gx); 206 | q3 += (qa * gz + qb * gy - qc * gx); 207 | 208 | // Normalise quaternion 209 | recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); 210 | q0 *= recipNorm; 211 | q1 *= recipNorm; 212 | q2 *= recipNorm; 213 | q3 *= recipNorm; 214 | } 215 | 216 | //--------------------------------------------------------------------------------------------------- 217 | // Fast inverse square-root 218 | // See: http://en.wikipedia.org/wiki/Fast_inverse_square_root 219 | 220 | float invSqrt(float x) { 221 | float halfx = 0.5f * x; 222 | float y = x; 223 | long i = *(long*)&y; 224 | i = 0x5f3759df - (i>>1); 225 | y = *(float*)&i; 226 | y = y * (1.5f - (halfx * y * y)); 227 | return y; 228 | } 229 | 230 | //==================================================================================================== 231 | // END OF CODE 232 | //==================================================================================================== 233 | -------------------------------------------------------------------------------- /MahonyAHRS/MahonyAHRS.h: -------------------------------------------------------------------------------- 1 | //===================================================================================================== 2 | // MahonyAHRS.h 3 | //===================================================================================================== 4 | // 5 | // Madgwick's implementation of Mayhony's AHRS algorithm. 6 | // See: http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms 7 | // 8 | // Date Author Notes 9 | // 29/09/2011 SOH Madgwick Initial release 10 | // 02/10/2011 SOH Madgwick Optimised for reduced CPU load 11 | // 12 | //===================================================================================================== 13 | #ifndef MahonyAHRS_h 14 | #define MahonyAHRS_h 15 | 16 | //---------------------------------------------------------------------------------------------------- 17 | // Variable declaration 18 | 19 | extern volatile float twoKp; // 2 * proportional gain (Kp) 20 | extern volatile float twoKi; // 2 * integral gain (Ki) 21 | extern volatile float q0, q1, q2, q3; // quaternion of sensor frame relative to auxiliary frame 22 | 23 | //--------------------------------------------------------------------------------------------------- 24 | // Function declarations 25 | 26 | void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz); 27 | void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az); 28 | 29 | #endif 30 | //===================================================================================================== 31 | // End of file 32 | //===================================================================================================== 33 | --------------------------------------------------------------------------------