QuaternionFilter.h 9.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223
  1. #pragma once
  2. #ifndef QUATERNIONFILTER_H
  3. #define QUATERNIONFILTER_H
  4. class QuaternionFilter
  5. {
  6. float GyroMeasError = PI * (40.0f / 180.0f); // gyroscope measurement error in rads/s (start at 40 deg/s)
  7. float GyroMeasDrift = PI * (0.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s)
  8. float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta
  9. float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift; // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value
  10. const float Kp = 2.0f * 5.0f; // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral
  11. const float Ki = 0.0f;
  12. float deltat = 0.0f, sum = 0.0f; // integration interval for both filter schemes
  13. uint32_t lastUpdate = 0, firstUpdate = 0; // used to calculate integration interval
  14. uint32_t Now = 0; // used to calculate integration interval
  15. // for mahony only
  16. float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method
  17. public:
  18. void bind() {}
  19. // MadgwickQuaternionUpdate
  20. void update(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz, float* q)
  21. {
  22. // updateParams()
  23. float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability
  24. float norm;
  25. float hx, hy, _2bx, _2bz;
  26. float s1, s2, s3, s4;
  27. float qDot1, qDot2, qDot3, qDot4;
  28. // Auxiliary variables to avoid repeated arithmetic
  29. float _2q1mx;
  30. float _2q1my;
  31. float _2q1mz;
  32. float _2q2mx;
  33. float _4bx;
  34. float _4bz;
  35. float _2q1 = 2.0f * q1;
  36. float _2q2 = 2.0f * q2;
  37. float _2q3 = 2.0f * q3;
  38. float _2q4 = 2.0f * q4;
  39. float _2q1q3 = 2.0f * q1 * q3;
  40. float _2q3q4 = 2.0f * q3 * q4;
  41. float q1q1 = q1 * q1;
  42. float q1q2 = q1 * q2;
  43. float q1q3 = q1 * q3;
  44. float q1q4 = q1 * q4;
  45. float q2q2 = q2 * q2;
  46. float q2q3 = q2 * q3;
  47. float q2q4 = q2 * q4;
  48. float q3q3 = q3 * q3;
  49. float q3q4 = q3 * q4;
  50. float q4q4 = q4 * q4;
  51. gx *= PI / 180.f;
  52. gy *= PI / 180.f;
  53. gz *= PI / 180.f;
  54. // updateTime()
  55. Now = micros();
  56. deltat = ((Now - lastUpdate) / 1000000.0f); // set integration time by time elapsed since last filter update
  57. lastUpdate = Now;
  58. // Normalise accelerometer measurement
  59. norm = sqrtf(ax * ax + ay * ay + az * az);
  60. if (norm == 0.0f) return; // handle NaN
  61. norm = 1.0f / norm;
  62. ax *= norm;
  63. ay *= norm;
  64. az *= norm;
  65. // Normalise magnetometer measurement
  66. norm = sqrtf(mx * mx + my * my + mz * mz);
  67. if (norm == 0.0f) return; // handle NaN
  68. norm = 1.0f / norm;
  69. mx *= norm;
  70. my *= norm;
  71. mz *= norm;
  72. // Reference direction of Earth's magnetic field
  73. _2q1mx = 2.0f * q1 * mx;
  74. _2q1my = 2.0f * q1 * my;
  75. _2q1mz = 2.0f * q1 * mz;
  76. _2q2mx = 2.0f * q2 * mx;
  77. hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4;
  78. hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4;
  79. _2bx = sqrtf(hx * hx + hy * hy);
  80. _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4;
  81. _4bx = 2.0f * _2bx;
  82. _4bz = 2.0f * _2bz;
  83. // Gradient decent algorithm corrective step
  84. 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);
  85. 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);
  86. 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);
  87. 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);
  88. norm = sqrtf(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude
  89. norm = 1.0f/norm;
  90. s1 *= norm;
  91. s2 *= norm;
  92. s3 *= norm;
  93. s4 *= norm;
  94. // Compute rate of change of quaternion
  95. qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1;
  96. qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2;
  97. qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3;
  98. qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4;
  99. // Integrate to yield quaternion
  100. q1 += qDot1 * deltat;
  101. q2 += qDot2 * deltat;
  102. q3 += qDot3 * deltat;
  103. q4 += qDot4 * deltat;
  104. norm = sqrtf(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion
  105. norm = 1.0f/norm;
  106. q[0] = q1 * norm;
  107. q[1] = q2 * norm;
  108. q[2] = q3 * norm;
  109. q[3] = q4 * norm;
  110. }
  111. // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and
  112. // measured ones.
  113. void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz, float* q)
  114. {
  115. float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability
  116. float norm;
  117. float hx, hy, bx, bz;
  118. float vx, vy, vz, wx, wy, wz;
  119. float ex, ey, ez;
  120. float pa, pb, pc;
  121. // Auxiliary variables to avoid repeated arithmetic
  122. float q1q1 = q1 * q1;
  123. float q1q2 = q1 * q2;
  124. float q1q3 = q1 * q3;
  125. float q1q4 = q1 * q4;
  126. float q2q2 = q2 * q2;
  127. float q2q3 = q2 * q3;
  128. float q2q4 = q2 * q4;
  129. float q3q3 = q3 * q3;
  130. float q3q4 = q3 * q4;
  131. float q4q4 = q4 * q4;
  132. // Normalise accelerometer measurement
  133. norm = sqrtf(ax * ax + ay * ay + az * az);
  134. if (norm == 0.0f) return; // handle NaN
  135. norm = 1.0f / norm; // use reciprocal for division
  136. ax *= norm;
  137. ay *= norm;
  138. az *= norm;
  139. // Normalise magnetometer measurement
  140. norm = sqrtf(mx * mx + my * my + mz * mz);
  141. if (norm == 0.0f) return; // handle NaN
  142. norm = 1.0f / norm; // use reciprocal for division
  143. mx *= norm;
  144. my *= norm;
  145. mz *= norm;
  146. // Reference direction of Earth's magnetic field
  147. hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3);
  148. hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2);
  149. bx = sqrtf((hx * hx) + (hy * hy));
  150. bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3);
  151. // Estimated direction of gravity and magnetic field
  152. vx = 2.0f * (q2q4 - q1q3);
  153. vy = 2.0f * (q1q2 + q3q4);
  154. vz = q1q1 - q2q2 - q3q3 + q4q4;
  155. wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3);
  156. wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4);
  157. wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3);
  158. // Error is cross product between estimated direction and measured direction of gravity
  159. ex = (ay * vz - az * vy) + (my * wz - mz * wy);
  160. ey = (az * vx - ax * vz) + (mz * wx - mx * wz);
  161. ez = (ax * vy - ay * vx) + (mx * wy - my * wx);
  162. if (Ki > 0.0f)
  163. {
  164. eInt[0] += ex; // accumulate integral error
  165. eInt[1] += ey;
  166. eInt[2] += ez;
  167. }
  168. else
  169. {
  170. eInt[0] = 0.0f; // prevent integral wind up
  171. eInt[1] = 0.0f;
  172. eInt[2] = 0.0f;
  173. }
  174. // Apply feedback terms
  175. gx = gx + Kp * ex + Ki * eInt[0];
  176. gy = gy + Kp * ey + Ki * eInt[1];
  177. gz = gz + Kp * ez + Ki * eInt[2];
  178. // Integrate rate of change of quaternion
  179. pa = q2;
  180. pb = q3;
  181. pc = q4;
  182. q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat);
  183. q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat);
  184. q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat);
  185. q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat);
  186. // Normalise quaternion
  187. norm = sqrtf(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);
  188. norm = 1.0f / norm;
  189. q[0] = q1 * norm;
  190. q[1] = q2 * norm;
  191. q[2] = q3 * norm;
  192. q[3] = q4 * norm;
  193. }
  194. };
  195. #endif // QUATERNIONFILTER_H