test_code / Mbed OS test_icm20948
Committer:
eric11fr
Date:
Mon Mar 29 21:16:25 2021 +0000
Revision:
1:8459e28d77a1
Parent:
0:efb1550773f1
icm20948

Who changed what in which revision?

UserRevisionLine numberNew contents of line
eric11fr 0:efb1550773f1 1 // Implementation of Sebastian Madgwick's "...efficient orientation filter
eric11fr 0:efb1550773f1 2 // for... inertial/magnetic sensor arrays"
eric11fr 0:efb1550773f1 3 // (see http://www.x-io.co.uk/category/open-source/ for examples & more details)
eric11fr 0:efb1550773f1 4 // which fuses acceleration, rotation rate, and magnetic moments to produce a
eric11fr 0:efb1550773f1 5 // quaternion-based estimate of absolute device orientation -- which can be
eric11fr 0:efb1550773f1 6 // converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc.
eric11fr 0:efb1550773f1 7 // The performance of the orientation filter is at least as good as conventional
eric11fr 0:efb1550773f1 8 // Kalman-based filtering algorithms but is much less computationally
eric11fr 0:efb1550773f1 9 // intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz!
eric11fr 0:efb1550773f1 10
eric11fr 1:8459e28d77a1 11 #include "ahrs.h"
eric11fr 1:8459e28d77a1 12 #include <math.h>
eric11fr 0:efb1550773f1 13 // These are the free parameters in the Mahony filter and fusion scheme, Kp
eric11fr 0:efb1550773f1 14 // for proportional feedback, Ki for integral
eric11fr 0:efb1550773f1 15 #define Kp 2.0f * 5.0f
eric11fr 0:efb1550773f1 16 #define Ki 0.0f
eric11fr 1:8459e28d77a1 17 typedef unsigned char byte;
eric11fr 0:efb1550773f1 18 static float GyroMeasError = PI * (40.0f / 180.0f);
eric11fr 0:efb1550773f1 19 // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s)
eric11fr 0:efb1550773f1 20 static float GyroMeasDrift = PI * (0.0f / 180.0f);
eric11fr 0:efb1550773f1 21 // There is a tradeoff in the beta parameter between accuracy and response
eric11fr 0:efb1550773f1 22 // speed. In the original Madgwick study, beta of 0.041 (corresponding to
eric11fr 0:efb1550773f1 23 // GyroMeasError of 2.7 degrees/s) was found to give optimal accuracy.
eric11fr 0:efb1550773f1 24 // However, with this value, the LSM9SD0 response time is about 10 seconds
eric11fr 0:efb1550773f1 25 // to a stable initial quaternion. Subsequent changes also require a
eric11fr 0:efb1550773f1 26 // longish lag time to a stable output, not fast enough for a quadcopter or
eric11fr 0:efb1550773f1 27 // robot car! By increasing beta (GyroMeasError) by about a factor of
eric11fr 0:efb1550773f1 28 // fifteen, the response time constant is reduced to ~2 sec. I haven't
eric11fr 0:efb1550773f1 29 // noticed any reduction in solution accuracy. This is essentially the I
eric11fr 0:efb1550773f1 30 // coefficient in a PID control sense; the bigger the feedback coefficient,
eric11fr 0:efb1550773f1 31 // the faster the solution converges, usually at the expense of accuracy.
eric11fr 0:efb1550773f1 32 // In any case, this is the free parameter in the Madgwick filtering and
eric11fr 0:efb1550773f1 33 // fusion scheme.
eric11fr 0:efb1550773f1 34 static float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // Compute beta
eric11fr 0:efb1550773f1 35 // Compute zeta, the other free parameter in the Madgwick scheme usually
eric11fr 0:efb1550773f1 36 // set to a small or zero value
eric11fr 0:efb1550773f1 37 static float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift;
eric11fr 0:efb1550773f1 38
eric11fr 0:efb1550773f1 39 // Vector to hold integral error for Mahony method
eric11fr 0:efb1550773f1 40 static float eInt[3] = {0.0f, 0.0f, 0.0f};
eric11fr 0:efb1550773f1 41 // Vector to hold quaternion
eric11fr 0:efb1550773f1 42 static float q[4] = {1.0f, 0.0f, 0.0f, 0.0f};
eric11fr 0:efb1550773f1 43
eric11fr 0:efb1550773f1 44 void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz, float deltat)
eric11fr 0:efb1550773f1 45 {
eric11fr 0:efb1550773f1 46 // short name local variable for readability
eric11fr 0:efb1550773f1 47 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3];
eric11fr 0:efb1550773f1 48 float norm;
eric11fr 0:efb1550773f1 49 float hx, hy, _2bx, _2bz;
eric11fr 0:efb1550773f1 50 float s1, s2, s3, s4;
eric11fr 0:efb1550773f1 51 float qDot1, qDot2, qDot3, qDot4;
eric11fr 0:efb1550773f1 52
eric11fr 0:efb1550773f1 53 // Auxiliary variables to avoid repeated arithmetic
eric11fr 0:efb1550773f1 54 float _2q1mx;
eric11fr 0:efb1550773f1 55 float _2q1my;
eric11fr 0:efb1550773f1 56 float _2q1mz;
eric11fr 0:efb1550773f1 57 float _2q2mx;
eric11fr 0:efb1550773f1 58 float _4bx;
eric11fr 0:efb1550773f1 59 float _4bz;
eric11fr 0:efb1550773f1 60 float _2q1 = 2.0f * q1;
eric11fr 0:efb1550773f1 61 float _2q2 = 2.0f * q2;
eric11fr 0:efb1550773f1 62 float _2q3 = 2.0f * q3;
eric11fr 0:efb1550773f1 63 float _2q4 = 2.0f * q4;
eric11fr 0:efb1550773f1 64 float _2q1q3 = 2.0f * q1 * q3;
eric11fr 0:efb1550773f1 65 float _2q3q4 = 2.0f * q3 * q4;
eric11fr 0:efb1550773f1 66 float q1q1 = q1 * q1;
eric11fr 0:efb1550773f1 67 float q1q2 = q1 * q2;
eric11fr 0:efb1550773f1 68 float q1q3 = q1 * q3;
eric11fr 0:efb1550773f1 69 float q1q4 = q1 * q4;
eric11fr 0:efb1550773f1 70 float q2q2 = q2 * q2;
eric11fr 0:efb1550773f1 71 float q2q3 = q2 * q3;
eric11fr 0:efb1550773f1 72 float q2q4 = q2 * q4;
eric11fr 0:efb1550773f1 73 float q3q3 = q3 * q3;
eric11fr 0:efb1550773f1 74 float q3q4 = q3 * q4;
eric11fr 0:efb1550773f1 75 float q4q4 = q4 * q4;
eric11fr 0:efb1550773f1 76
eric11fr 0:efb1550773f1 77 // Normalise accelerometer measurement
eric11fr 0:efb1550773f1 78 norm = sqrt(ax * ax + ay * ay + az * az);
eric11fr 0:efb1550773f1 79 if (norm == 0.0f) return; // handle NaN
eric11fr 0:efb1550773f1 80 norm = 1.0f/norm;
eric11fr 0:efb1550773f1 81 ax *= norm;
eric11fr 0:efb1550773f1 82 ay *= norm;
eric11fr 0:efb1550773f1 83 az *= norm;
eric11fr 0:efb1550773f1 84
eric11fr 0:efb1550773f1 85 // Normalise magnetometer measurement
eric11fr 0:efb1550773f1 86 norm = sqrt(mx * mx + my * my + mz * mz);
eric11fr 0:efb1550773f1 87 if (norm == 0.0f) return; // handle NaN
eric11fr 0:efb1550773f1 88 norm = 1.0f/norm;
eric11fr 0:efb1550773f1 89 mx *= norm;
eric11fr 0:efb1550773f1 90 my *= norm;
eric11fr 0:efb1550773f1 91 mz *= norm;
eric11fr 0:efb1550773f1 92
eric11fr 0:efb1550773f1 93 // Reference direction of Earth's magnetic field
eric11fr 0:efb1550773f1 94 _2q1mx = 2.0f * q1 * mx;
eric11fr 0:efb1550773f1 95 _2q1my = 2.0f * q1 * my;
eric11fr 0:efb1550773f1 96 _2q1mz = 2.0f * q1 * mz;
eric11fr 0:efb1550773f1 97 _2q2mx = 2.0f * q2 * mx;
eric11fr 0:efb1550773f1 98 hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 +
eric11fr 0:efb1550773f1 99 _2q2 * mz * q4 - mx * q3q3 - mx * q4q4;
eric11fr 0:efb1550773f1 100 hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4;
eric11fr 0:efb1550773f1 101 _2bx = sqrt(hx * hx + hy * hy);
eric11fr 0:efb1550773f1 102 _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4;
eric11fr 0:efb1550773f1 103 _4bx = 2.0f * _2bx;
eric11fr 0:efb1550773f1 104 _4bz = 2.0f * _2bz;
eric11fr 0:efb1550773f1 105
eric11fr 0:efb1550773f1 106 // Gradient decent algorithm corrective step
eric11fr 0:efb1550773f1 107 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);
eric11fr 0:efb1550773f1 108 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);
eric11fr 0:efb1550773f1 109 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);
eric11fr 0:efb1550773f1 110 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);
eric11fr 0:efb1550773f1 111 norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude
eric11fr 0:efb1550773f1 112 norm = 1.0f/norm;
eric11fr 0:efb1550773f1 113 s1 *= norm;
eric11fr 0:efb1550773f1 114 s2 *= norm;
eric11fr 0:efb1550773f1 115 s3 *= norm;
eric11fr 0:efb1550773f1 116 s4 *= norm;
eric11fr 0:efb1550773f1 117
eric11fr 0:efb1550773f1 118 // Compute rate of change of quaternion
eric11fr 0:efb1550773f1 119 qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1;
eric11fr 0:efb1550773f1 120 qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2;
eric11fr 0:efb1550773f1 121 qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3;
eric11fr 0:efb1550773f1 122 qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4;
eric11fr 0:efb1550773f1 123
eric11fr 0:efb1550773f1 124 // Integrate to yield quaternion
eric11fr 0:efb1550773f1 125 q1 += qDot1 * deltat;
eric11fr 0:efb1550773f1 126 q2 += qDot2 * deltat;
eric11fr 0:efb1550773f1 127 q3 += qDot3 * deltat;
eric11fr 0:efb1550773f1 128 q4 += qDot4 * deltat;
eric11fr 0:efb1550773f1 129 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion
eric11fr 0:efb1550773f1 130 norm = 1.0f/norm;
eric11fr 0:efb1550773f1 131 q[0] = q1 * norm;
eric11fr 0:efb1550773f1 132 q[1] = q2 * norm;
eric11fr 0:efb1550773f1 133 q[2] = q3 * norm;
eric11fr 0:efb1550773f1 134 q[3] = q4 * norm;
eric11fr 0:efb1550773f1 135 }
eric11fr 0:efb1550773f1 136
eric11fr 0:efb1550773f1 137
eric11fr 0:efb1550773f1 138
eric11fr 0:efb1550773f1 139 // Similar to Madgwick scheme but uses proportional and integral filtering on
eric11fr 0:efb1550773f1 140 // the error between estimated reference vectors and measured ones.
eric11fr 0:efb1550773f1 141 void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz, float deltat)
eric11fr 0:efb1550773f1 142 {
eric11fr 0:efb1550773f1 143 // short name local variable for readability
eric11fr 0:efb1550773f1 144 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3];
eric11fr 0:efb1550773f1 145 float norm;
eric11fr 0:efb1550773f1 146 float hx, hy, bx, bz;
eric11fr 0:efb1550773f1 147 float vx, vy, vz, wx, wy, wz;
eric11fr 0:efb1550773f1 148 float ex, ey, ez;
eric11fr 0:efb1550773f1 149 float pa, pb, pc;
eric11fr 0:efb1550773f1 150
eric11fr 0:efb1550773f1 151 // Auxiliary variables to avoid repeated arithmetic
eric11fr 0:efb1550773f1 152 float q1q1 = q1 * q1;
eric11fr 0:efb1550773f1 153 float q1q2 = q1 * q2;
eric11fr 0:efb1550773f1 154 float q1q3 = q1 * q3;
eric11fr 0:efb1550773f1 155 float q1q4 = q1 * q4;
eric11fr 0:efb1550773f1 156 float q2q2 = q2 * q2;
eric11fr 0:efb1550773f1 157 float q2q3 = q2 * q3;
eric11fr 0:efb1550773f1 158 float q2q4 = q2 * q4;
eric11fr 0:efb1550773f1 159 float q3q3 = q3 * q3;
eric11fr 0:efb1550773f1 160 float q3q4 = q3 * q4;
eric11fr 0:efb1550773f1 161 float q4q4 = q4 * q4;
eric11fr 0:efb1550773f1 162
eric11fr 0:efb1550773f1 163 // Normalise accelerometer measurement
eric11fr 0:efb1550773f1 164 norm = sqrt(ax * ax + ay * ay + az * az);
eric11fr 0:efb1550773f1 165 if (norm == 0.0f) return; // Handle NaN
eric11fr 0:efb1550773f1 166 norm = 1.0f / norm; // Use reciprocal for division
eric11fr 0:efb1550773f1 167 ax *= norm;
eric11fr 0:efb1550773f1 168 ay *= norm;
eric11fr 0:efb1550773f1 169 az *= norm;
eric11fr 0:efb1550773f1 170
eric11fr 0:efb1550773f1 171 // Normalise magnetometer measurement
eric11fr 0:efb1550773f1 172 norm = sqrt(mx * mx + my * my + mz * mz);
eric11fr 0:efb1550773f1 173 if (norm == 0.0f) return; // Handle NaN
eric11fr 0:efb1550773f1 174 norm = 1.0f / norm; // Use reciprocal for division
eric11fr 0:efb1550773f1 175 mx *= norm;
eric11fr 0:efb1550773f1 176 my *= norm;
eric11fr 0:efb1550773f1 177 mz *= norm;
eric11fr 0:efb1550773f1 178
eric11fr 0:efb1550773f1 179 // Reference direction of Earth's magnetic field
eric11fr 0:efb1550773f1 180 hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3);
eric11fr 0:efb1550773f1 181 hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2);
eric11fr 0:efb1550773f1 182 bx = sqrt((hx * hx) + (hy * hy));
eric11fr 0:efb1550773f1 183 bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3);
eric11fr 0:efb1550773f1 184
eric11fr 0:efb1550773f1 185 // Estimated direction of gravity and magnetic field
eric11fr 0:efb1550773f1 186 vx = 2.0f * (q2q4 - q1q3);
eric11fr 0:efb1550773f1 187 vy = 2.0f * (q1q2 + q3q4);
eric11fr 0:efb1550773f1 188 vz = q1q1 - q2q2 - q3q3 + q4q4;
eric11fr 0:efb1550773f1 189 wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3);
eric11fr 0:efb1550773f1 190 wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4);
eric11fr 0:efb1550773f1 191 wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3);
eric11fr 0:efb1550773f1 192
eric11fr 0:efb1550773f1 193 // Error is cross product between estimated direction and measured direction of gravity
eric11fr 0:efb1550773f1 194 ex = (ay * vz - az * vy) + (my * wz - mz * wy);
eric11fr 0:efb1550773f1 195 ey = (az * vx - ax * vz) + (mz * wx - mx * wz);
eric11fr 0:efb1550773f1 196 ez = (ax * vy - ay * vx) + (mx * wy - my * wx);
eric11fr 0:efb1550773f1 197 if (Ki > 0.0f)
eric11fr 0:efb1550773f1 198 {
eric11fr 0:efb1550773f1 199 eInt[0] += ex; // accumulate integral error
eric11fr 0:efb1550773f1 200 eInt[1] += ey;
eric11fr 0:efb1550773f1 201 eInt[2] += ez;
eric11fr 0:efb1550773f1 202 }
eric11fr 0:efb1550773f1 203 else
eric11fr 0:efb1550773f1 204 {
eric11fr 0:efb1550773f1 205 eInt[0] = 0.0f; // prevent integral wind up
eric11fr 0:efb1550773f1 206 eInt[1] = 0.0f;
eric11fr 0:efb1550773f1 207 eInt[2] = 0.0f;
eric11fr 0:efb1550773f1 208 }
eric11fr 0:efb1550773f1 209
eric11fr 0:efb1550773f1 210 // Apply feedback terms
eric11fr 0:efb1550773f1 211 gx = gx + Kp * ex + Ki * eInt[0];
eric11fr 0:efb1550773f1 212 gy = gy + Kp * ey + Ki * eInt[1];
eric11fr 0:efb1550773f1 213 gz = gz + Kp * ez + Ki * eInt[2];
eric11fr 0:efb1550773f1 214
eric11fr 0:efb1550773f1 215 // Integrate rate of change of quaternion
eric11fr 0:efb1550773f1 216 pa = q2;
eric11fr 0:efb1550773f1 217 pb = q3;
eric11fr 0:efb1550773f1 218 pc = q4;
eric11fr 0:efb1550773f1 219 q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat);
eric11fr 0:efb1550773f1 220 q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat);
eric11fr 0:efb1550773f1 221 q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat);
eric11fr 0:efb1550773f1 222 q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat);
eric11fr 0:efb1550773f1 223
eric11fr 0:efb1550773f1 224 // Normalise quaternion
eric11fr 0:efb1550773f1 225 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);
eric11fr 0:efb1550773f1 226 norm = 1.0f / norm;
eric11fr 0:efb1550773f1 227 q[0] = q1 * norm;
eric11fr 0:efb1550773f1 228 q[1] = q2 * norm;
eric11fr 0:efb1550773f1 229 q[2] = q3 * norm;
eric11fr 0:efb1550773f1 230 q[3] = q4 * norm;
eric11fr 0:efb1550773f1 231 }
eric11fr 0:efb1550773f1 232
eric11fr 0:efb1550773f1 233 const float * getQ () { return q; }