AHRS Library

Committer:
altb
Date:
Tue Dec 04 15:49:48 2018 +0000
Revision:
3:6811c0ce95f6
Parent:
1:36bbe04e1f6f
AHRS Klasse mit Mahony filter etc

Who changed what in which revision?

UserRevisionLine numberNew contents of line
altb 0:6661e1395e30 1 //=============================================================================================
altb 0:6661e1395e30 2 // MadgwickAHRS.c
altb 0:6661e1395e30 3 //=============================================================================================
altb 0:6661e1395e30 4 //
altb 0:6661e1395e30 5 // Implementation of Madgwick's IMU and AHRS algorithms.
altb 0:6661e1395e30 6 // See: http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/
altb 0:6661e1395e30 7 //
altb 0:6661e1395e30 8 // From the x-io website "Open-source resources available on this website are
altb 0:6661e1395e30 9 // provided under the GNU General Public Licence unless an alternative licence
altb 0:6661e1395e30 10 // is provided in source."
altb 0:6661e1395e30 11 //
altb 0:6661e1395e30 12 // Date Author Notes
altb 0:6661e1395e30 13 // 29/09/2011 SOH Madgwick Initial release
altb 0:6661e1395e30 14 // 02/10/2011 SOH Madgwick Optimised for reduced CPU load
altb 0:6661e1395e30 15 // 19/02/2012 SOH Madgwick Magnetometer measurement is normalised
altb 0:6661e1395e30 16 // 18/12/2016 Added better fast inverse square root
altb 0:6661e1395e30 17 //
altb 0:6661e1395e30 18 //=============================================================================================
altb 0:6661e1395e30 19
altb 0:6661e1395e30 20 //-------------------------------------------------------------------------------------------
altb 0:6661e1395e30 21 // Header files
altb 0:6661e1395e30 22
altb 0:6661e1395e30 23 #include "MadgwickAHRS.h"
altb 0:6661e1395e30 24 #include <math.h>
altb 0:6661e1395e30 25
altb 0:6661e1395e30 26 //-------------------------------------------------------------------------------------------
altb 0:6661e1395e30 27 // Definitions
altb 0:6661e1395e30 28
altb 1:36bbe04e1f6f 29 #define betaDef 0.25f // 2 * proportional gain 0.1 - 0.5 - 5; 8
altb 0:6661e1395e30 30
altb 0:6661e1395e30 31
altb 0:6661e1395e30 32 //============================================================================================
altb 0:6661e1395e30 33 // Functions
altb 0:6661e1395e30 34
altb 0:6661e1395e30 35 //-------------------------------------------------------------------------------------------
altb 0:6661e1395e30 36 // AHRS algorithm update
altb 0:6661e1395e30 37
altb 3:6811c0ce95f6 38 Madgwick::Madgwick(float Ts) {
altb 0:6661e1395e30 39 beta = betaDef;
altb 0:6661e1395e30 40 q0 = 1.0f;
altb 0:6661e1395e30 41 q1 = 0.0f;
altb 0:6661e1395e30 42 q2 = 0.0f;
altb 0:6661e1395e30 43 q3 = 0.0f;
altb 3:6811c0ce95f6 44 invSampleFreq = Ts;
altb 0:6661e1395e30 45 anglesComputed = 0;
altb 0:6661e1395e30 46 }
altb 0:6661e1395e30 47
altb 0:6661e1395e30 48 void Madgwick::update(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz) {
altb 0:6661e1395e30 49 float recipNorm;
altb 0:6661e1395e30 50 float s0, s1, s2, s3;
altb 0:6661e1395e30 51 float qDot1, qDot2, qDot3, qDot4;
altb 0:6661e1395e30 52 float hx, hy;
altb 0:6661e1395e30 53 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;
altb 0:6661e1395e30 54
altb 0:6661e1395e30 55 // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation)
altb 0:6661e1395e30 56 if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) {
altb 0:6661e1395e30 57 updateIMU(gx, gy, gz, ax, ay, az);
altb 0:6661e1395e30 58 return;
altb 0:6661e1395e30 59 }
altb 0:6661e1395e30 60
altb 0:6661e1395e30 61 // Convert gyroscope degrees/sec to radians/sec
altb 0:6661e1395e30 62 gx *= 0.0174533f;
altb 0:6661e1395e30 63 gy *= 0.0174533f;
altb 0:6661e1395e30 64 gz *= 0.0174533f;
altb 0:6661e1395e30 65
altb 0:6661e1395e30 66 // Rate of change of quaternion from gyroscope
altb 0:6661e1395e30 67 qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz);
altb 0:6661e1395e30 68 qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy);
altb 0:6661e1395e30 69 qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx);
altb 0:6661e1395e30 70 qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx);
altb 0:6661e1395e30 71
altb 0:6661e1395e30 72 // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
altb 0:6661e1395e30 73 if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) {
altb 0:6661e1395e30 74
altb 0:6661e1395e30 75 // Normalise accelerometer measurement
altb 0:6661e1395e30 76 recipNorm = invSqrt(ax * ax + ay * ay + az * az);
altb 0:6661e1395e30 77 ax *= recipNorm;
altb 0:6661e1395e30 78 ay *= recipNorm;
altb 0:6661e1395e30 79 az *= recipNorm;
altb 0:6661e1395e30 80
altb 0:6661e1395e30 81 // Normalise magnetometer measurement
altb 0:6661e1395e30 82 recipNorm = invSqrt(mx * mx + my * my + mz * mz);
altb 0:6661e1395e30 83 mx *= recipNorm;
altb 0:6661e1395e30 84 my *= recipNorm;
altb 0:6661e1395e30 85 mz *= recipNorm;
altb 0:6661e1395e30 86
altb 0:6661e1395e30 87 // Auxiliary variables to avoid repeated arithmetic
altb 0:6661e1395e30 88 _2q0mx = 2.0f * q0 * mx;
altb 0:6661e1395e30 89 _2q0my = 2.0f * q0 * my;
altb 0:6661e1395e30 90 _2q0mz = 2.0f * q0 * mz;
altb 0:6661e1395e30 91 _2q1mx = 2.0f * q1 * mx;
altb 0:6661e1395e30 92 _2q0 = 2.0f * q0;
altb 0:6661e1395e30 93 _2q1 = 2.0f * q1;
altb 0:6661e1395e30 94 _2q2 = 2.0f * q2;
altb 0:6661e1395e30 95 _2q3 = 2.0f * q3;
altb 0:6661e1395e30 96 _2q0q2 = 2.0f * q0 * q2;
altb 0:6661e1395e30 97 _2q2q3 = 2.0f * q2 * q3;
altb 0:6661e1395e30 98 q0q0 = q0 * q0;
altb 0:6661e1395e30 99 q0q1 = q0 * q1;
altb 0:6661e1395e30 100 q0q2 = q0 * q2;
altb 0:6661e1395e30 101 q0q3 = q0 * q3;
altb 0:6661e1395e30 102 q1q1 = q1 * q1;
altb 0:6661e1395e30 103 q1q2 = q1 * q2;
altb 0:6661e1395e30 104 q1q3 = q1 * q3;
altb 0:6661e1395e30 105 q2q2 = q2 * q2;
altb 0:6661e1395e30 106 q2q3 = q2 * q3;
altb 0:6661e1395e30 107 q3q3 = q3 * q3;
altb 0:6661e1395e30 108
altb 0:6661e1395e30 109 // Reference direction of Earth's magnetic field
altb 0:6661e1395e30 110 hx = mx * q0q0 - _2q0my * q3 + _2q0mz * q2 + mx * q1q1 + _2q1 * my * q2 + _2q1 * mz * q3 - mx * q2q2 - mx * q3q3;
altb 0:6661e1395e30 111 hy = _2q0mx * q3 + my * q0q0 - _2q0mz * q1 + _2q1mx * q2 - my * q1q1 + my * q2q2 + _2q2 * mz * q3 - my * q3q3;
altb 0:6661e1395e30 112 _2bx = sqrtf(hx * hx + hy * hy);
altb 0:6661e1395e30 113 _2bz = -_2q0mx * q2 + _2q0my * q1 + mz * q0q0 + _2q1mx * q3 - mz * q1q1 + _2q2 * my * q3 - mz * q2q2 + mz * q3q3;
altb 0:6661e1395e30 114 _4bx = 2.0f * _2bx;
altb 0:6661e1395e30 115 _4bz = 2.0f * _2bz;
altb 0:6661e1395e30 116
altb 0:6661e1395e30 117 // Gradient decent algorithm corrective step
altb 0:6661e1395e30 118 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);
altb 0:6661e1395e30 119 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);
altb 0:6661e1395e30 120 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);
altb 0:6661e1395e30 121 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);
altb 0:6661e1395e30 122 recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude
altb 0:6661e1395e30 123 s0 *= recipNorm;
altb 0:6661e1395e30 124 s1 *= recipNorm;
altb 0:6661e1395e30 125 s2 *= recipNorm;
altb 0:6661e1395e30 126 s3 *= recipNorm;
altb 0:6661e1395e30 127
altb 0:6661e1395e30 128 // Apply feedback step
altb 0:6661e1395e30 129 qDot1 -= beta * s0;
altb 0:6661e1395e30 130 qDot2 -= beta * s1;
altb 0:6661e1395e30 131 qDot3 -= beta * s2;
altb 0:6661e1395e30 132 qDot4 -= beta * s3;
altb 0:6661e1395e30 133 }
altb 0:6661e1395e30 134
altb 0:6661e1395e30 135 // Integrate rate of change of quaternion to yield quaternion
altb 0:6661e1395e30 136 q0 += qDot1 * invSampleFreq;
altb 0:6661e1395e30 137 q1 += qDot2 * invSampleFreq;
altb 0:6661e1395e30 138 q2 += qDot3 * invSampleFreq;
altb 0:6661e1395e30 139 q3 += qDot4 * invSampleFreq;
altb 0:6661e1395e30 140
altb 0:6661e1395e30 141 // Normalise quaternion
altb 0:6661e1395e30 142 recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
altb 0:6661e1395e30 143 q0 *= recipNorm;
altb 0:6661e1395e30 144 q1 *= recipNorm;
altb 0:6661e1395e30 145 q2 *= recipNorm;
altb 0:6661e1395e30 146 q3 *= recipNorm;
altb 0:6661e1395e30 147 anglesComputed = 0;
altb 0:6661e1395e30 148 }
altb 0:6661e1395e30 149
altb 0:6661e1395e30 150 //-------------------------------------------------------------------------------------------
altb 0:6661e1395e30 151 // IMU algorithm update
altb 0:6661e1395e30 152
altb 0:6661e1395e30 153 void Madgwick::updateIMU(float gx, float gy, float gz, float ax, float ay, float az) {
altb 0:6661e1395e30 154 float recipNorm;
altb 0:6661e1395e30 155 float s0, s1, s2, s3;
altb 0:6661e1395e30 156 float qDot1, qDot2, qDot3, qDot4;
altb 0:6661e1395e30 157 float _2q0, _2q1, _2q2, _2q3, _4q0, _4q1, _4q2 ,_8q1, _8q2, q0q0, q1q1, q2q2, q3q3;
altb 0:6661e1395e30 158
altb 0:6661e1395e30 159 // Convert gyroscope degrees/sec to radians/sec
altb 0:6661e1395e30 160 gx *= 0.0174533f;
altb 0:6661e1395e30 161 gy *= 0.0174533f;
altb 0:6661e1395e30 162 gz *= 0.0174533f;
altb 0:6661e1395e30 163
altb 0:6661e1395e30 164 // Rate of change of quaternion from gyroscope
altb 0:6661e1395e30 165 qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz);
altb 0:6661e1395e30 166 qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy);
altb 0:6661e1395e30 167 qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx);
altb 0:6661e1395e30 168 qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx);
altb 0:6661e1395e30 169
altb 0:6661e1395e30 170 // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
altb 0:6661e1395e30 171 if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) {
altb 0:6661e1395e30 172
altb 0:6661e1395e30 173 // Normalise accelerometer measurement
altb 0:6661e1395e30 174 recipNorm = invSqrt(ax * ax + ay * ay + az * az);
altb 0:6661e1395e30 175 ax *= recipNorm;
altb 0:6661e1395e30 176 ay *= recipNorm;
altb 0:6661e1395e30 177 az *= recipNorm;
altb 0:6661e1395e30 178
altb 0:6661e1395e30 179 // Auxiliary variables to avoid repeated arithmetic
altb 0:6661e1395e30 180 _2q0 = 2.0f * q0;
altb 0:6661e1395e30 181 _2q1 = 2.0f * q1;
altb 0:6661e1395e30 182 _2q2 = 2.0f * q2;
altb 0:6661e1395e30 183 _2q3 = 2.0f * q3;
altb 0:6661e1395e30 184 _4q0 = 4.0f * q0;
altb 0:6661e1395e30 185 _4q1 = 4.0f * q1;
altb 0:6661e1395e30 186 _4q2 = 4.0f * q2;
altb 0:6661e1395e30 187 _8q1 = 8.0f * q1;
altb 0:6661e1395e30 188 _8q2 = 8.0f * q2;
altb 0:6661e1395e30 189 q0q0 = q0 * q0;
altb 0:6661e1395e30 190 q1q1 = q1 * q1;
altb 0:6661e1395e30 191 q2q2 = q2 * q2;
altb 0:6661e1395e30 192 q3q3 = q3 * q3;
altb 0:6661e1395e30 193
altb 0:6661e1395e30 194 // Gradient decent algorithm corrective step
altb 0:6661e1395e30 195 s0 = _4q0 * q2q2 + _2q2 * ax + _4q0 * q1q1 - _2q1 * ay;
altb 0:6661e1395e30 196 s1 = _4q1 * q3q3 - _2q3 * ax + 4.0f * q0q0 * q1 - _2q0 * ay - _4q1 + _8q1 * q1q1 + _8q1 * q2q2 + _4q1 * az;
altb 0:6661e1395e30 197 s2 = 4.0f * q0q0 * q2 + _2q0 * ax + _4q2 * q3q3 - _2q3 * ay - _4q2 + _8q2 * q1q1 + _8q2 * q2q2 + _4q2 * az;
altb 0:6661e1395e30 198 s3 = 4.0f * q1q1 * q3 - _2q1 * ax + 4.0f * q2q2 * q3 - _2q2 * ay;
altb 0:6661e1395e30 199 recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude
altb 0:6661e1395e30 200 s0 *= recipNorm;
altb 0:6661e1395e30 201 s1 *= recipNorm;
altb 0:6661e1395e30 202 s2 *= recipNorm;
altb 0:6661e1395e30 203 s3 *= recipNorm;
altb 0:6661e1395e30 204
altb 0:6661e1395e30 205 // Apply feedback step
altb 0:6661e1395e30 206 qDot1 -= beta * s0;
altb 0:6661e1395e30 207 qDot2 -= beta * s1;
altb 0:6661e1395e30 208 qDot3 -= beta * s2;
altb 0:6661e1395e30 209 qDot4 -= beta * s3;
altb 0:6661e1395e30 210 }
altb 0:6661e1395e30 211
altb 0:6661e1395e30 212 // Integrate rate of change of quaternion to yield quaternion
altb 0:6661e1395e30 213 q0 += qDot1 * invSampleFreq;
altb 0:6661e1395e30 214 q1 += qDot2 * invSampleFreq;
altb 0:6661e1395e30 215 q2 += qDot3 * invSampleFreq;
altb 0:6661e1395e30 216 q3 += qDot4 * invSampleFreq;
altb 0:6661e1395e30 217
altb 0:6661e1395e30 218 // Normalise quaternion
altb 0:6661e1395e30 219 recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
altb 0:6661e1395e30 220 q0 *= recipNorm;
altb 0:6661e1395e30 221 q1 *= recipNorm;
altb 0:6661e1395e30 222 q2 *= recipNorm;
altb 0:6661e1395e30 223 q3 *= recipNorm;
altb 0:6661e1395e30 224 anglesComputed = 0;
altb 0:6661e1395e30 225 }
altb 0:6661e1395e30 226
altb 0:6661e1395e30 227 //-------------------------------------------------------------------------------------------
altb 0:6661e1395e30 228 // Fast inverse square-root
altb 0:6661e1395e30 229 // See: http://en.wikipedia.org/wiki/Fast_inverse_square_root
altb 0:6661e1395e30 230
altb 0:6661e1395e30 231 /*float Madgwick::invSqrt(float x) {
altb 0:6661e1395e30 232 float halfx = 0.5f * x;
altb 0:6661e1395e30 233 float y = x;
altb 0:6661e1395e30 234 long i = *(long*)&y;
altb 0:6661e1395e30 235 i = 0x5f3759df - (i>>1);
altb 0:6661e1395e30 236 y = *(float*)&i;
altb 0:6661e1395e30 237 y = y * (1.5f - (halfx * y * y));
altb 0:6661e1395e30 238 y = y * (1.5f - (halfx * y * y));
altb 0:6661e1395e30 239 return y;
altb 0:6661e1395e30 240 } */
altb 0:6661e1395e30 241
altb 0:6661e1395e30 242 float Madgwick::invSqrt(float x){
altb 0:6661e1395e30 243 unsigned int i = 0x5F1F1412 - (*(unsigned int*)&x >> 1);
altb 0:6661e1395e30 244 float tmp = *(float*)&i;
altb 0:6661e1395e30 245 return tmp * (1.69000231f - 0.714158168f * x * tmp * tmp);
altb 0:6661e1395e30 246 }
altb 0:6661e1395e30 247
altb 0:6661e1395e30 248 //-------------------------------------------------------------------------------------------
altb 0:6661e1395e30 249
altb 0:6661e1395e30 250 void Madgwick::computeAngles()
altb 0:6661e1395e30 251 {
altb 0:6661e1395e30 252 roll = atan2f(q0*q1 + q2*q3, 0.5f - q1*q1 - q2*q2);
altb 0:6661e1395e30 253 pitch = asinf(-2.0f * (q1*q3 - q0*q2));
altb 0:6661e1395e30 254 yaw = atan2f(q1*q2 + q0*q3, 0.5f - q2*q2 - q3*q3);
altb 0:6661e1395e30 255 anglesComputed = 1;
altb 0:6661e1395e30 256 }