Madgewick Filter to get attitude from IMU or MARG. Confirmed IMU ver works well.
Dependents: NineIMUAttitude_MadgwickFilter
MadgwickFilter.hpp@8:72c013425ecc, 2020-08-21 (annotated)
- Committer:
- aktk
- Date:
- Fri Aug 21 03:13:08 2020 +0000
- Revision:
- 8:72c013425ecc
- Parent:
- 7:c20656d96585
Forked and modified some parts
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
Gaku0606 | 0:c160cac4c370 | 1 | #ifndef _MADGWICK_FILTER_HPP_ |
Gaku0606 | 0:c160cac4c370 | 2 | #define _MADGWICK_FILTER_HPP_ |
Gaku0606 | 0:c160cac4c370 | 3 | |
Gaku0606 | 0:c160cac4c370 | 4 | #include "mbed.h" |
Gaku0606 | 0:c160cac4c370 | 5 | #include "Quaternion.hpp" |
Gaku0606 | 0:c160cac4c370 | 6 | |
Gaku0606 | 0:c160cac4c370 | 7 | #define BETA_DEF 0.1 |
Gaku0606 | 0:c160cac4c370 | 8 | |
aktk | 8:72c013425ecc | 9 | |
Gaku0606 | 0:c160cac4c370 | 10 | /** |
Gaku0606 | 2:e1de76e257f6 | 11 | * @bref Madgwick Filterを用いて,角速度・加速度・地磁気データを統合し,姿勢を推定するライブラリです. |
Gaku0606 | 2:e1de76e257f6 | 12 | * @note Quaternion.hppを利用されることをお勧めいたします. |
Gaku0606 | 0:c160cac4c370 | 13 | */ |
aktk | 8:72c013425ecc | 14 | class MadgwickFilter |
aktk | 8:72c013425ecc | 15 | { |
aktk | 8:72c013425ecc | 16 | |
Gaku0606 | 0:c160cac4c370 | 17 | public: |
Gaku0606 | 0:c160cac4c370 | 18 | /** |
Gaku0606 | 2:e1de76e257f6 | 19 | @bref マドグウィックフィルター(マッジュウィックフィルター)クラスのコンストラクタ |
Gaku0606 | 0:c160cac4c370 | 20 | @param B double型, この値を大きくすると重力の影響を大きく取るようになります. |
Gaku0606 | 0:c160cac4c370 | 21 | @note 引数無しの場合,B = 0.1fが代入されます. |
Gaku0606 | 0:c160cac4c370 | 22 | */ |
aktk | 8:72c013425ecc | 23 | MadgwickFilter(float B = BETA_DEF, float dT_sec = 0.05f); |
aktk | 8:72c013425ecc | 24 | |
Gaku0606 | 0:c160cac4c370 | 25 | public: |
Gaku0606 | 0:c160cac4c370 | 26 | /** |
Gaku0606 | 0:c160cac4c370 | 27 | @bref MadgwickFilterによって角速度・加速度・地磁気データを統合し,姿勢計算します. |
Gaku0606 | 0:c160cac4c370 | 28 | @param gx,gy,gz 角速度データ,[rad]に変換してから入れてください. |
Gaku0606 | 0:c160cac4c370 | 29 | @param ax,ay,az 加速度データ, 特に規格化は必要ありません |
Gaku0606 | 0:c160cac4c370 | 30 | @param mx,my,mz 地磁気データ, キャリブレーションを確実に行って下さい. |
Gaku0606 | 0:c160cac4c370 | 31 | @note 角速度は[rad]にしてください.この関数は出来るだけ高速に呼び出し続けた方が良いと思います. |
Gaku0606 | 0:c160cac4c370 | 32 | @note 外部でローパスフィルタなどをかけることをお勧めします. |
Gaku0606 | 0:c160cac4c370 | 33 | */ |
Gaku0606 | 6:eff5ebc4ea13 | 34 | void MadgwickAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz); |
aktk | 8:72c013425ecc | 35 | |
aktk | 8:72c013425ecc | 36 | /** |
aktk | 8:72c013425ecc | 37 | @bref MadgwickFilterによって角速度・加速度・地磁気データを統合し,姿勢計算します. |
aktk | 8:72c013425ecc | 38 | @param gyro 角速度データ,[rad]に変換してから入れてください. |
aktk | 8:72c013425ecc | 39 | @param acc 加速度データ, 特に規格化は必要ありません |
aktk | 8:72c013425ecc | 40 | @param mag 地磁気データ, キャリブレーションを確実に行って下さい. |
aktk | 8:72c013425ecc | 41 | @note 角速度は[rad]にしてください.この関数は出来るだけ高速に呼び出し続けた方が良いと思います. |
aktk | 8:72c013425ecc | 42 | @note 外部でローパスフィルタなどをかけることをお勧めします. |
Gaku0606 | 7:c20656d96585 | 43 | */ |
Gaku0606 | 7:c20656d96585 | 44 | void MadgwickAHRSupdate(float *gyro, float *acc, float *mag); |
aktk | 8:72c013425ecc | 45 | |
Gaku0606 | 0:c160cac4c370 | 46 | /** |
Gaku0606 | 0:c160cac4c370 | 47 | @bref MadgwickFilterを角速度と加速度のみで動かし,姿勢計算を更新します. |
Gaku0606 | 0:c160cac4c370 | 48 | @param gx,gy,gz 角速度データ,[rad]に変換してから入れてください. |
Gaku0606 | 0:c160cac4c370 | 49 | @param ax,ay,az 加速度データ, 特に規格化は必要ありません |
Gaku0606 | 0:c160cac4c370 | 50 | @note 通常の関数でも,地磁気成分を0.0にすればこの関数が呼ばれます. |
Gaku0606 | 0:c160cac4c370 | 51 | */ |
Gaku0606 | 6:eff5ebc4ea13 | 52 | void MadgwickAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az); |
aktk | 8:72c013425ecc | 53 | |
Gaku0606 | 0:c160cac4c370 | 54 | /** |
Gaku0606 | 0:c160cac4c370 | 55 | @bref 姿勢を四元数で取得します. |
Gaku0606 | 0:c160cac4c370 | 56 | @param Q クォータニオンクラスのインスタンスアドレス, w・i・j・kを更新します. |
Gaku0606 | 0:c160cac4c370 | 57 | @note unityに入れる際は軸方向を修正してください. |
Gaku0606 | 0:c160cac4c370 | 58 | */ |
Gaku0606 | 0:c160cac4c370 | 59 | void getAttitude(Quaternion *Q); |
aktk | 8:72c013425ecc | 60 | |
Gaku0606 | 0:c160cac4c370 | 61 | /** |
Gaku0606 | 0:c160cac4c370 | 62 | @bref 姿勢を四元数で取得します. |
Gaku0606 | 0:c160cac4c370 | 63 | @param _q0 実部w, double型, アドレス |
Gaku0606 | 0:c160cac4c370 | 64 | @param _q1 虚部i, double型, アドレス |
Gaku0606 | 0:c160cac4c370 | 65 | @param _q2 虚部j, double型, アドレス |
Gaku0606 | 0:c160cac4c370 | 66 | @param _q3 虚部k, double型, アドレス |
Gaku0606 | 0:c160cac4c370 | 67 | @note unityに入れる際は軸方向を修正してください. |
Gaku0606 | 0:c160cac4c370 | 68 | */ |
Gaku0606 | 6:eff5ebc4ea13 | 69 | void getAttitude(float *_q0, float *_q1, float *_q2, float *_q3); |
aktk | 8:72c013425ecc | 70 | |
Gaku0606 | 0:c160cac4c370 | 71 | /** |
Gaku0606 | 0:c160cac4c370 | 72 | @bref オイラー角で姿勢を取得します. |
Gaku0606 | 0:c160cac4c370 | 73 | @param val ロール,ピッチ,ヨーの順に配列に格納します.3つ以上の要素の配列を入れてください. |
Gaku0606 | 0:c160cac4c370 | 74 | @note 値は[rad]です.[degree]に変換が必要な場合は別途計算して下さい. |
Gaku0606 | 0:c160cac4c370 | 75 | */ |
Gaku0606 | 6:eff5ebc4ea13 | 76 | void getEulerAngle(float *val); |
Gaku0606 | 0:c160cac4c370 | 77 | public: |
Gaku0606 | 0:c160cac4c370 | 78 | Timer madgwickTimer; |
Gaku0606 | 0:c160cac4c370 | 79 | Quaternion q; |
Gaku0606 | 6:eff5ebc4ea13 | 80 | float q0,q1,q2,q3; |
aktk | 8:72c013425ecc | 81 | float beta; |
aktk | 8:72c013425ecc | 82 | float zeta; |
aktk | 8:72c013425ecc | 83 | float deltaT_sec; |
aktk | 8:72c013425ecc | 84 | static int counter_numofojbect; |
aktk | 8:72c013425ecc | 85 | int ID; |
aktk | 8:72c013425ecc | 86 | |
aktk | 8:72c013425ecc | 87 | // Var for UpadateIMU |
aktk | 8:72c013425ecc | 88 | private: |
aktk | 8:72c013425ecc | 89 | float deltaT; |
aktk | 8:72c013425ecc | 90 | unsigned int newTime, oldTime; |
aktk | 8:72c013425ecc | 91 | float recipNorm; |
aktk | 8:72c013425ecc | 92 | float s0, s1, s2, s3; |
aktk | 8:72c013425ecc | 93 | float qDot1, qDot2, qDot3, qDot4; |
aktk | 8:72c013425ecc | 94 | float _2q0, _2q1, _2q2, _2q3, _4q0, _4q1, _4q2,_8q1, _8q2, q0q0, q1q1, q2q2, q3q3; |
aktk | 8:72c013425ecc | 95 | float acc_norm; |
Gaku0606 | 0:c160cac4c370 | 96 | }; |
Gaku0606 | 0:c160cac4c370 | 97 | |
aktk | 8:72c013425ecc | 98 | int MadgwickFilter::counter_numofojbect = 0; |
aktk | 8:72c013425ecc | 99 | |
aktk | 8:72c013425ecc | 100 | MadgwickFilter::MadgwickFilter(float B, float dT_sec) |
aktk | 8:72c013425ecc | 101 | { |
aktk | 8:72c013425ecc | 102 | ID = counter_numofojbect; |
aktk | 8:72c013425ecc | 103 | counter_numofojbect++; |
Gaku0606 | 0:c160cac4c370 | 104 | q.w = 1.0f; |
Gaku0606 | 0:c160cac4c370 | 105 | q.x = 0.0f; |
Gaku0606 | 0:c160cac4c370 | 106 | q.y = 0.0f; |
Gaku0606 | 0:c160cac4c370 | 107 | q.z = 0.0f; |
Gaku0606 | 0:c160cac4c370 | 108 | beta = B; |
aktk | 8:72c013425ecc | 109 | zeta = beta * 0.2 /5; |
aktk | 8:72c013425ecc | 110 | deltaT_sec = dT_sec; |
Gaku0606 | 0:c160cac4c370 | 111 | q0 = 1.0f; |
Gaku0606 | 0:c160cac4c370 | 112 | q1 = 0.0f; |
Gaku0606 | 0:c160cac4c370 | 113 | q2 = 0.0f; |
aktk | 8:72c013425ecc | 114 | q3 = 0.0f; |
Gaku0606 | 0:c160cac4c370 | 115 | madgwickTimer.start(); |
Gaku0606 | 0:c160cac4c370 | 116 | } |
Gaku0606 | 0:c160cac4c370 | 117 | |
aktk | 8:72c013425ecc | 118 | void MadgwickFilter::getAttitude(Quaternion *Q) |
aktk | 8:72c013425ecc | 119 | { |
Gaku0606 | 0:c160cac4c370 | 120 | *Q = q; |
aktk | 8:72c013425ecc | 121 | return; |
Gaku0606 | 0:c160cac4c370 | 122 | } |
Gaku0606 | 0:c160cac4c370 | 123 | |
Gaku0606 | 0:c160cac4c370 | 124 | |
Gaku0606 | 0:c160cac4c370 | 125 | |
aktk | 8:72c013425ecc | 126 | void MadgwickFilter::getAttitude(float *_q0, float *_q1, float *_q2, float *_q3) |
aktk | 8:72c013425ecc | 127 | { |
Gaku0606 | 0:c160cac4c370 | 128 | *_q0 = q0; |
Gaku0606 | 0:c160cac4c370 | 129 | *_q1 = q1; |
Gaku0606 | 0:c160cac4c370 | 130 | *_q2 = q2; |
Gaku0606 | 0:c160cac4c370 | 131 | *_q3 = q3; |
aktk | 8:72c013425ecc | 132 | return; |
Gaku0606 | 0:c160cac4c370 | 133 | } |
Gaku0606 | 0:c160cac4c370 | 134 | |
Gaku0606 | 0:c160cac4c370 | 135 | |
aktk | 8:72c013425ecc | 136 | void MadgwickFilter::getEulerAngle(float *val) |
aktk | 8:72c013425ecc | 137 | { |
Gaku0606 | 6:eff5ebc4ea13 | 138 | float q0q0 = q0 * q0, q1q1q2q2 = q1 * q1 - q2 * q2, q3q3 = q3 * q3; |
Gaku0606 | 0:c160cac4c370 | 139 | val[0] = (atan2(2.0f * (q0 * q1 + q2 * q3), q0q0 - q1q1q2q2 + q3q3)); |
Gaku0606 | 0:c160cac4c370 | 140 | val[1] = (-asin(2.0f * (q1 * q3 - q0 * q2))); |
Gaku0606 | 0:c160cac4c370 | 141 | val[2] = (atan2(2.0f * (q1 * q2 + q0 * q3), q0q0 + q1q1q2q2 - q3q3)); |
Gaku0606 | 0:c160cac4c370 | 142 | } |
Gaku0606 | 0:c160cac4c370 | 143 | //--------------------------------------------------------------------------------------------------- |
Gaku0606 | 0:c160cac4c370 | 144 | // AHRS algorithm update |
Gaku0606 | 0:c160cac4c370 | 145 | |
aktk | 8:72c013425ecc | 146 | inline void MadgwickFilter::MadgwickAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz) |
aktk | 8:72c013425ecc | 147 | { |
aktk | 8:72c013425ecc | 148 | |
aktk | 8:72c013425ecc | 149 | static float acc_norm; |
aktk | 8:72c013425ecc | 150 | static float deltaT = 0.0f; |
aktk | 8:72c013425ecc | 151 | static unsigned int newTime = 0, oldTime = 0; |
aktk | 8:72c013425ecc | 152 | static float recipNorm; |
aktk | 8:72c013425ecc | 153 | static float s0, s1, s2, s3; |
aktk | 8:72c013425ecc | 154 | static float qDot1, qDot2, qDot3, qDot4; |
aktk | 8:72c013425ecc | 155 | static float w_bx = 0, w_by = 0, w_bz = 0; |
aktk | 8:72c013425ecc | 156 | static float hx=0, hy=0, hz=0; |
aktk | 8:72c013425ecc | 157 | static float init_itr = 0; |
aktk | 8:72c013425ecc | 158 | //static float _2q0mx, _2q0my, _2q0mz, _2q1mx, bx = 0.0f, bz = 1.0f, _2bx, _2bz, _2q0, _2q1, _2q2, _2q3, _2q0q2, _2q2q3, q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; |
aktk | 8:72c013425ecc | 159 | static float _2q0mx, _2q0my, _2q0mz, _2q1mx, bx = 0.0f, bz = 1.0f, _2bx, _2bz, _2q0, _2q1, _2q2, _2q3, _2q0q2, _2q2q3, q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; |
aktk | 8:72c013425ecc | 160 | |
aktk | 8:72c013425ecc | 161 | /* |
aktk | 8:72c013425ecc | 162 | // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation) |
aktk | 8:72c013425ecc | 163 | if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { |
aktk | 8:72c013425ecc | 164 | MadgwickAHRSupdateIMU(gx, gy, gz, ax, ay, az); |
aktk | 8:72c013425ecc | 165 | return; |
aktk | 8:72c013425ecc | 166 | } |
aktk | 8:72c013425ecc | 167 | */ |
aktk | 8:72c013425ecc | 168 | |
aktk | 8:72c013425ecc | 169 | // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) |
aktk | 8:72c013425ecc | 170 | if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { |
aktk | 8:72c013425ecc | 171 | |
aktk | 8:72c013425ecc | 172 | // Normalise accelerometer measurement |
aktk | 8:72c013425ecc | 173 | acc_norm = sqrt(ax * ax + ay * ay + az * az); |
aktk | 8:72c013425ecc | 174 | recipNorm = 1.0f / acc_norm; |
aktk | 8:72c013425ecc | 175 | ax *= recipNorm; |
aktk | 8:72c013425ecc | 176 | ay *= recipNorm; |
aktk | 8:72c013425ecc | 177 | az *= recipNorm; |
aktk | 8:72c013425ecc | 178 | |
aktk | 8:72c013425ecc | 179 | // Normalise magnetometer measurement |
aktk | 8:72c013425ecc | 180 | if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { |
aktk | 8:72c013425ecc | 181 | recipNorm = 1.0f; |
aktk | 8:72c013425ecc | 182 | } else { |
aktk | 8:72c013425ecc | 183 | recipNorm = 1.0f / sqrt(mx * mx + my * my + mz * mz); |
aktk | 8:72c013425ecc | 184 | } |
aktk | 8:72c013425ecc | 185 | mx *= recipNorm; |
aktk | 8:72c013425ecc | 186 | my *= recipNorm; |
aktk | 8:72c013425ecc | 187 | mz *= recipNorm; |
aktk | 8:72c013425ecc | 188 | |
aktk | 8:72c013425ecc | 189 | // Auxiliary variables to avoid repeated arithmetic |
aktk | 8:72c013425ecc | 190 | _2q0mx = 2.0f * q0 * mx; |
aktk | 8:72c013425ecc | 191 | _2q0my = 2.0f * q0 * my; |
aktk | 8:72c013425ecc | 192 | _2q0mz = 2.0f * q0 * mz; |
aktk | 8:72c013425ecc | 193 | _2q1mx = 2.0f * q1 * mx; |
aktk | 8:72c013425ecc | 194 | _2q0 = 2.0f * q0; |
aktk | 8:72c013425ecc | 195 | _2q1 = 2.0f * q1; |
aktk | 8:72c013425ecc | 196 | _2q2 = 2.0f * q2; |
aktk | 8:72c013425ecc | 197 | _2q3 = 2.0f * q3; |
aktk | 8:72c013425ecc | 198 | _2q0q2 = 2.0f * q0 * q2; |
aktk | 8:72c013425ecc | 199 | _2q2q3 = 2.0f * q2 * q3; |
aktk | 8:72c013425ecc | 200 | q0q0 = q0 * q0; |
aktk | 8:72c013425ecc | 201 | q0q1 = q0 * q1; |
aktk | 8:72c013425ecc | 202 | q0q2 = q0 * q2; |
aktk | 8:72c013425ecc | 203 | q0q3 = q0 * q3; |
aktk | 8:72c013425ecc | 204 | q1q1 = q1 * q1; |
aktk | 8:72c013425ecc | 205 | q1q2 = q1 * q2; |
aktk | 8:72c013425ecc | 206 | q1q3 = q1 * q3; |
aktk | 8:72c013425ecc | 207 | q2q2 = q2 * q2; |
aktk | 8:72c013425ecc | 208 | q2q3 = q2 * q3; |
aktk | 8:72c013425ecc | 209 | q3q3 = q3 * q3; |
aktk | 8:72c013425ecc | 210 | |
aktk | 8:72c013425ecc | 211 | // Reference direction of Earth's magnetic field |
aktk | 8:72c013425ecc | 212 | //hx = mx * q0q0 - _2q0my * q3 + _2q0mz * q2 + mx * q1q1 + _2q1 * my * q2 + _2q1 * mz * q3 - mx * q2q2 - mx * q3q3; |
aktk | 8:72c013425ecc | 213 | //hx = mx * (q0q0 + q1q1 - q2q2 - q3q3) + 2.0f * my * (q1q2 - q0q3) + 2.0f * mz * (q1q3 + q0q2); |
aktk | 8:72c013425ecc | 214 | hx = mx |
aktk | 8:72c013425ecc | 215 | - 2.0f * mx * (q2q2 + q3q3) |
aktk | 8:72c013425ecc | 216 | + 2.0f * my * (q1q2 - q0q3) |
aktk | 8:72c013425ecc | 217 | + 2.0f * mz * (q1q3 + q0q2); |
aktk | 8:72c013425ecc | 218 | |
aktk | 8:72c013425ecc | 219 | //hy = _2q0mx * q3 + my * q0q0 - _2q0mz * q1 + _2q1mx * q2 - my * q1q1 + my * q2q2 + _2q2 * mz * q3 - my * q3q3; |
aktk | 8:72c013425ecc | 220 | //hy = 2.0f * mx * (q0q3 + q1q2) + my * (q0q0 - q1q1 + q2q2 - q3q3) + 2.0f * mz * (q2q3 - q0q1); |
aktk | 8:72c013425ecc | 221 | hy = 2.0f * mx * (q1q2 + q0q3) |
aktk | 8:72c013425ecc | 222 | + my |
aktk | 8:72c013425ecc | 223 | - 2.0f * my * (q1q1 + q3q3) |
aktk | 8:72c013425ecc | 224 | + 2.0f * mz * (q2q3 - q0q1); |
aktk | 8:72c013425ecc | 225 | |
aktk | 8:72c013425ecc | 226 | //hz = -_2q0mx * q2 + _2q0my * q1 + mz * q0q0 + _2q1mx * q3 - mz * q1q1 + _2q2 * my * q3 - mz * q2q2 + mz * q3q3; |
aktk | 8:72c013425ecc | 227 | hz = 2.0f * mx * (q1q3 - q0q2) |
aktk | 8:72c013425ecc | 228 | + 2.0f * my * (q2q3 + q0q1) |
aktk | 8:72c013425ecc | 229 | + mz |
aktk | 8:72c013425ecc | 230 | - 2.0f * mz * (q1q1 + q2q2); |
aktk | 8:72c013425ecc | 231 | |
aktk | 8:72c013425ecc | 232 | |
aktk | 8:72c013425ecc | 233 | bx = sqrt(hx * hx + hy * hy); |
aktk | 8:72c013425ecc | 234 | bz = hz; |
aktk | 8:72c013425ecc | 235 | |
aktk | 8:72c013425ecc | 236 | _2bx = 2.0f * bx; |
aktk | 8:72c013425ecc | 237 | _2bz = 2.0f * bz; |
aktk | 8:72c013425ecc | 238 | |
aktk | 8:72c013425ecc | 239 | //aux |
aktk | 8:72c013425ecc | 240 | float f_0 = _2q1 * q3 - _2q0 * q2 - ax; |
aktk | 8:72c013425ecc | 241 | float f_1 = _2q0 * q1 + _2q2 * q3 - ay; |
aktk | 8:72c013425ecc | 242 | float f_2 = 1.0f - _2q1 * q1 - _2q2 * q2 - az; |
aktk | 8:72c013425ecc | 243 | float f_3 = _2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx; |
aktk | 8:72c013425ecc | 244 | float f_4 = _2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my; |
aktk | 8:72c013425ecc | 245 | float f_5 = _2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz; |
aktk | 8:72c013425ecc | 246 | float J_00or13 = _2q2; // J_00 negated in matrix multiplication |
aktk | 8:72c013425ecc | 247 | float J_01or12 = 2.0f * q3; |
aktk | 8:72c013425ecc | 248 | float J_02or11 = _2q0; // J_02 negated in matrix multiplication |
aktk | 8:72c013425ecc | 249 | float J_03or10 = _2q1; |
aktk | 8:72c013425ecc | 250 | float J_21 = 2.0f * J_03or10; // negated in matrix multiplication |
aktk | 8:72c013425ecc | 251 | float J_22 = 2.0f * J_00or13; // negated in matrix multiplication |
aktk | 8:72c013425ecc | 252 | float J_30 = _2bz*q2; // negated in matrix multiplication |
aktk | 8:72c013425ecc | 253 | float J_31 = _2bz*q3; |
aktk | 8:72c013425ecc | 254 | float J_32 = 2.0f * _2bx*q2 + _2bz*q0; // negated in matrix multiplication |
aktk | 8:72c013425ecc | 255 | float J_33 = 2.0f * _2bx*q3 - _2bz*q1; // negated in matrix multiplication |
aktk | 8:72c013425ecc | 256 | float J_40 = _2bx*q3 - _2bz*q1; // negated in matrix multiplication |
aktk | 8:72c013425ecc | 257 | float J_41 = _2bx*q2 + _2bz*q0; |
aktk | 8:72c013425ecc | 258 | float J_42 = _2bx*q1 + _2bz*q3; |
aktk | 8:72c013425ecc | 259 | float J_43 = _2bx*q0 - _2bz*q2; // negated in matrix multiplication |
aktk | 8:72c013425ecc | 260 | float J_50 = _2bx*q2; |
aktk | 8:72c013425ecc | 261 | float J_51 = _2bx*q3 - 2.0f * _2bz*q1; |
aktk | 8:72c013425ecc | 262 | float J_52 = _2bx*q0 - 2.0f * _2bz*q2; |
aktk | 8:72c013425ecc | 263 | float J_53 = _2bx*q1; |
aktk | 8:72c013425ecc | 264 | |
aktk | 8:72c013425ecc | 265 | // Gradient decent algorithm corrective step |
aktk | 8:72c013425ecc | 266 | /* |
aktk | 8:72c013425ecc | 267 | 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); |
aktk | 8:72c013425ecc | 268 | s1 = _2q3 * (2.0f * q1q3 - _2q0q2 - ax) + _2q0 * (2.0f * q0q1 + _2q2q3 - ay) - 4.0f * q1 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + bz * q3 * (bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2) - mx) + (bx * q2 + bz * q0) * (bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3) - my) + (bx * q3 - _2bz * q1) * (bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2) - mz); |
aktk | 8:72c013425ecc | 269 | s2 = -_2q0 * (2.0f * q1q3 - _2q0q2 - ax) + _2q3 * (2.0f * q0q1 + _2q2q3 - ay) - 4.0f * q2 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + (-_2bx * q2 - bz * q0) * (bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2) - mx) + (bx * q1 + bz * q3) * (bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3) - my) + (bx * q0 - _2bz * q2) * (bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2) - mz); |
aktk | 8:72c013425ecc | 270 | s3 = _2q1 * (2.0f * q1q3 - _2q0q2 - ax) + _2q2 * (2.0f * q0q1 + _2q2q3 - ay) + (-_2bx * q3 + bz * q1) * (bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2) - mx) + (-bx * q0 + bz * q2) * (bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3) - my) + bx * q1 * (bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2) - mz); |
aktk | 8:72c013425ecc | 271 | */ |
aktk | 8:72c013425ecc | 272 | s0 = J_03or10 * f_1 - J_00or13 * f_0 - J_30 * f_3 - J_40 * f_4 + J_50 * f_5; |
aktk | 8:72c013425ecc | 273 | s1 = J_01or12 * f_0 + J_02or11 * f_1 - J_21 * f_2 + J_31 * f_3 + J_41 * f_4 + J_51 * f_5; |
aktk | 8:72c013425ecc | 274 | s2 = J_01or12 * f_1 - J_22 * f_2 - J_02or11 * f_0 - J_32 * f_3 + J_42 * f_4 + J_52 * f_5; |
aktk | 8:72c013425ecc | 275 | s3 = J_03or10 * f_0 + J_00or13 * f_1 - J_33 * f_3 - J_43 * f_4 + J_53 * f_5; |
aktk | 8:72c013425ecc | 276 | |
aktk | 8:72c013425ecc | 277 | recipNorm = 1.0f / sqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude |
aktk | 8:72c013425ecc | 278 | s0 *= recipNorm; |
aktk | 8:72c013425ecc | 279 | s1 *= recipNorm; |
aktk | 8:72c013425ecc | 280 | s2 *= recipNorm; |
aktk | 8:72c013425ecc | 281 | s3 *= recipNorm; |
aktk | 8:72c013425ecc | 282 | |
aktk | 8:72c013425ecc | 283 | } |
aktk | 8:72c013425ecc | 284 | |
aktk | 8:72c013425ecc | 285 | // Integrate rate of change of quaternion to yield quaternion |
aktk | 8:72c013425ecc | 286 | newTime = (unsigned int)madgwickTimer.read_us(); |
aktk | 8:72c013425ecc | 287 | deltaT = (newTime - oldTime) / 1000000.0f; |
aktk | 8:72c013425ecc | 288 | deltaT = fabs(deltaT); |
aktk | 8:72c013425ecc | 289 | oldTime = newTime; |
aktk | 8:72c013425ecc | 290 | |
aktk | 8:72c013425ecc | 291 | // compute angular estimated direction of the gyroscope error |
aktk | 8:72c013425ecc | 292 | float w_err_x = _2q0 * s1 - _2q1 * s0 - _2q2 * s3 + _2q3 * s2; |
aktk | 8:72c013425ecc | 293 | float w_err_y = _2q0 * s2 + _2q1 * s3 - _2q2 * s0 - _2q3 * s1; |
aktk | 8:72c013425ecc | 294 | float w_err_z = _2q0 * s3 - _2q1 * s2 + _2q2 * s1 - _2q3 * s0; |
aktk | 8:72c013425ecc | 295 | // compute and remove the gyroscope baises |
aktk | 8:72c013425ecc | 296 | w_bx += w_err_x * deltaT * zeta; |
aktk | 8:72c013425ecc | 297 | w_by += w_err_y * deltaT * zeta; |
aktk | 8:72c013425ecc | 298 | w_bz += w_err_z * deltaT * zeta; |
aktk | 8:72c013425ecc | 299 | gx -= w_bx; |
aktk | 8:72c013425ecc | 300 | gy -= w_by; |
aktk | 8:72c013425ecc | 301 | gz -= w_bz; |
aktk | 8:72c013425ecc | 302 | |
aktk | 8:72c013425ecc | 303 | |
aktk | 8:72c013425ecc | 304 | |
aktk | 8:72c013425ecc | 305 | // Rate of change of quaternion from gyroscope |
aktk | 8:72c013425ecc | 306 | qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); |
aktk | 8:72c013425ecc | 307 | qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); |
aktk | 8:72c013425ecc | 308 | qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); |
aktk | 8:72c013425ecc | 309 | qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); |
aktk | 8:72c013425ecc | 310 | |
aktk | 8:72c013425ecc | 311 | q0 += (qDot1 - beta * s0) * deltaT;//(1.0f / sampleFreq); |
aktk | 8:72c013425ecc | 312 | q1 += (qDot2 - beta * s1) * deltaT;//(1.0f / sampleFreq); |
aktk | 8:72c013425ecc | 313 | q2 += (qDot3 - beta * s2) * deltaT;//(1.0f / sampleFreq); |
aktk | 8:72c013425ecc | 314 | q3 += (qDot4 - beta * s3) * deltaT;//(1.0f / sampleFreq); |
aktk | 8:72c013425ecc | 315 | |
aktk | 8:72c013425ecc | 316 | // Normalise quaternion |
aktk | 8:72c013425ecc | 317 | recipNorm = 1.0f / sqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); |
aktk | 8:72c013425ecc | 318 | q0 *= recipNorm; |
aktk | 8:72c013425ecc | 319 | q1 *= recipNorm; |
aktk | 8:72c013425ecc | 320 | q2 *= recipNorm; |
aktk | 8:72c013425ecc | 321 | q3 *= recipNorm; |
aktk | 8:72c013425ecc | 322 | |
aktk | 8:72c013425ecc | 323 | q.w = q0; |
aktk | 8:72c013425ecc | 324 | q.x = q1; |
aktk | 8:72c013425ecc | 325 | q.y = q2; |
aktk | 8:72c013425ecc | 326 | q.z = q3; |
aktk | 8:72c013425ecc | 327 | } |
aktk | 8:72c013425ecc | 328 | |
aktk | 8:72c013425ecc | 329 | inline void MadgwickFilter::MadgwickAHRSupdate(float *gyro, float *acc, float *mag) |
aktk | 8:72c013425ecc | 330 | { |
aktk | 8:72c013425ecc | 331 | |
aktk | 8:72c013425ecc | 332 | static float gx = 0, gy = 0, gz = 0.0f, ax = 0.0f, ay = 0.0f, az = 0.0f, mx = 0.0f, my = 0.0f, mz = 0.0f; |
Gaku0606 | 6:eff5ebc4ea13 | 333 | static float acc_norm; |
Gaku0606 | 6:eff5ebc4ea13 | 334 | static float deltaT = 0.0f; |
Gaku0606 | 0:c160cac4c370 | 335 | static unsigned int newTime = 0, oldTime = 0; |
Gaku0606 | 6:eff5ebc4ea13 | 336 | static float recipNorm; |
Gaku0606 | 6:eff5ebc4ea13 | 337 | static float s0, s1, s2, s3; |
Gaku0606 | 6:eff5ebc4ea13 | 338 | static float qDot1, qDot2, qDot3, qDot4; |
Gaku0606 | 6:eff5ebc4ea13 | 339 | static float hx, hy; |
aktk | 8:72c013425ecc | 340 | static float _2q0mx, _2q0my, _2q0mz, _2q1mx, bx, bz, _2bx, _2bz, _2q0, _2q1, _2q2, _2q3, _2q0q2, _2q2q3, q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; |
aktk | 8:72c013425ecc | 341 | |
aktk | 8:72c013425ecc | 342 | gx = gyro[0]; |
aktk | 8:72c013425ecc | 343 | gy = gyro[1]; |
aktk | 8:72c013425ecc | 344 | gz = gyro[2]; |
aktk | 8:72c013425ecc | 345 | ax = acc[0]; |
aktk | 8:72c013425ecc | 346 | ay = acc[1]; |
aktk | 8:72c013425ecc | 347 | az = acc[2]; |
aktk | 8:72c013425ecc | 348 | mx = mag[0]; |
aktk | 8:72c013425ecc | 349 | my = mag[1]; |
aktk | 8:72c013425ecc | 350 | mz = mag[2]; |
Gaku0606 | 0:c160cac4c370 | 351 | |
Gaku0606 | 0:c160cac4c370 | 352 | // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation) |
Gaku0606 | 0:c160cac4c370 | 353 | if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { |
Gaku0606 | 0:c160cac4c370 | 354 | MadgwickAHRSupdateIMU(gx, gy, gz, ax, ay, az); |
Gaku0606 | 0:c160cac4c370 | 355 | return; |
Gaku0606 | 0:c160cac4c370 | 356 | } |
Gaku0606 | 0:c160cac4c370 | 357 | |
Gaku0606 | 0:c160cac4c370 | 358 | // Rate of change of quaternion from gyroscope |
Gaku0606 | 0:c160cac4c370 | 359 | qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); |
Gaku0606 | 0:c160cac4c370 | 360 | qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); |
Gaku0606 | 0:c160cac4c370 | 361 | qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); |
Gaku0606 | 0:c160cac4c370 | 362 | qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); |
Gaku0606 | 0:c160cac4c370 | 363 | |
Gaku0606 | 0:c160cac4c370 | 364 | // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) |
Gaku0606 | 0:c160cac4c370 | 365 | if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { |
Gaku0606 | 0:c160cac4c370 | 366 | |
Gaku0606 | 0:c160cac4c370 | 367 | // Normalise accelerometer measurement |
Gaku0606 | 5:1e6fecaea25e | 368 | acc_norm = sqrt(ax * ax + ay * ay + az * az); |
Gaku0606 | 6:eff5ebc4ea13 | 369 | recipNorm = 1.0f / acc_norm; |
Gaku0606 | 0:c160cac4c370 | 370 | ax *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 371 | ay *= recipNorm; |
aktk | 8:72c013425ecc | 372 | az *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 373 | |
Gaku0606 | 0:c160cac4c370 | 374 | // Normalise magnetometer measurement |
Gaku0606 | 6:eff5ebc4ea13 | 375 | recipNorm = 1.0f / sqrt(mx * mx + my * my + mz * mz); |
Gaku0606 | 0:c160cac4c370 | 376 | mx *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 377 | my *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 378 | mz *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 379 | |
Gaku0606 | 0:c160cac4c370 | 380 | // Auxiliary variables to avoid repeated arithmetic |
Gaku0606 | 0:c160cac4c370 | 381 | _2q0mx = 2.0f * q0 * mx; |
Gaku0606 | 0:c160cac4c370 | 382 | _2q0my = 2.0f * q0 * my; |
Gaku0606 | 0:c160cac4c370 | 383 | _2q0mz = 2.0f * q0 * mz; |
Gaku0606 | 0:c160cac4c370 | 384 | _2q1mx = 2.0f * q1 * mx; |
Gaku0606 | 0:c160cac4c370 | 385 | _2q0 = 2.0f * q0; |
Gaku0606 | 0:c160cac4c370 | 386 | _2q1 = 2.0f * q1; |
Gaku0606 | 0:c160cac4c370 | 387 | _2q2 = 2.0f * q2; |
Gaku0606 | 0:c160cac4c370 | 388 | _2q3 = 2.0f * q3; |
Gaku0606 | 0:c160cac4c370 | 389 | _2q0q2 = 2.0f * q0 * q2; |
Gaku0606 | 0:c160cac4c370 | 390 | _2q2q3 = 2.0f * q2 * q3; |
Gaku0606 | 0:c160cac4c370 | 391 | q0q0 = q0 * q0; |
Gaku0606 | 0:c160cac4c370 | 392 | q0q1 = q0 * q1; |
Gaku0606 | 0:c160cac4c370 | 393 | q0q2 = q0 * q2; |
Gaku0606 | 0:c160cac4c370 | 394 | q0q3 = q0 * q3; |
Gaku0606 | 0:c160cac4c370 | 395 | q1q1 = q1 * q1; |
Gaku0606 | 0:c160cac4c370 | 396 | q1q2 = q1 * q2; |
Gaku0606 | 0:c160cac4c370 | 397 | q1q3 = q1 * q3; |
Gaku0606 | 0:c160cac4c370 | 398 | q2q2 = q2 * q2; |
Gaku0606 | 0:c160cac4c370 | 399 | q2q3 = q2 * q3; |
Gaku0606 | 0:c160cac4c370 | 400 | q3q3 = q3 * q3; |
Gaku0606 | 0:c160cac4c370 | 401 | |
Gaku0606 | 0:c160cac4c370 | 402 | // Reference direction of Earth's magnetic field |
Gaku0606 | 0:c160cac4c370 | 403 | hx = mx * q0q0 - _2q0my * q3 + _2q0mz * q2 + mx * q1q1 + _2q1 * my * q2 + _2q1 * mz * q3 - mx * q2q2 - mx * q3q3; |
Gaku0606 | 0:c160cac4c370 | 404 | hy = _2q0mx * q3 + my * q0q0 - _2q0mz * q1 + _2q1mx * q2 - my * q1q1 + my * q2q2 + _2q2 * mz * q3 - my * q3q3; |
aktk | 8:72c013425ecc | 405 | bx = sqrt(hx * hx + hy * hy); |
aktk | 8:72c013425ecc | 406 | bz = -_2q0mx * q2 + _2q0my * q1 + mz * q0q0 + _2q1mx * q3 - mz * q1q1 + _2q2 * my * q3 - mz * q2q2 + mz * q3q3; |
aktk | 8:72c013425ecc | 407 | _2bx = 2.0f * bx; |
aktk | 8:72c013425ecc | 408 | _2bz = 2.0f * bz; |
Gaku0606 | 0:c160cac4c370 | 409 | |
Gaku0606 | 0:c160cac4c370 | 410 | // Gradient decent algorithm corrective step |
aktk | 8:72c013425ecc | 411 | s0 = -_2q2 * (2.0f * q1q3 - _2q0q2 - ax) + _2q1 * (2.0f * q0q1 + _2q2q3 - ay) - bz * q2 * (bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2) - mx) + (-bx * q3 + bz * q1) * (bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3) - my) + bx * q2 * (bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2) - mz); |
aktk | 8:72c013425ecc | 412 | s1 = _2q3 * (2.0f * q1q3 - _2q0q2 - ax) + _2q0 * (2.0f * q0q1 + _2q2q3 - ay) - 4.0f * q1 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + bz * q3 * (bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2) - mx) + (bx * q2 + bz * q0) * (bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3) - my) + (bx * q3 - _2bz * q1) * (bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2) - mz); |
aktk | 8:72c013425ecc | 413 | s2 = -_2q0 * (2.0f * q1q3 - _2q0q2 - ax) + _2q3 * (2.0f * q0q1 + _2q2q3 - ay) - 4.0f * q2 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + (-_2bx * q2 - bz * q0) * (bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2) - mx) + (bx * q1 + bz * q3) * (bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3) - my) + (bx * q0 - _2bz * q2) * (bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2) - mz); |
aktk | 8:72c013425ecc | 414 | s3 = _2q1 * (2.0f * q1q3 - _2q0q2 - ax) + _2q2 * (2.0f * q0q1 + _2q2q3 - ay) + (-_2bx * q3 + bz * q1) * (bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2) - mx) + (-bx * q0 + bz * q2) * (bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3) - my) + bx * q1 * (bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2) - mz); |
Gaku0606 | 6:eff5ebc4ea13 | 415 | recipNorm = 1.0f / sqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude |
Gaku0606 | 0:c160cac4c370 | 416 | s0 *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 417 | s1 *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 418 | s2 *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 419 | s3 *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 420 | |
Gaku0606 | 6:eff5ebc4ea13 | 421 | float deltaA = fabs(acc_norm - 1.00f); |
Gaku0606 | 5:1e6fecaea25e | 422 | //beta = 0.1*exp(-1.0*deltaA*deltaA); |
Gaku0606 | 5:1e6fecaea25e | 423 | //beta = 0.3*exp(-20.0*deltaA*deltaA); |
Gaku0606 | 7:c20656d96585 | 424 | //beta = beta*exp(-30.0f*deltaA*deltaA); |
Gaku0606 | 5:1e6fecaea25e | 425 | //printf("%f\r\n", beta); |
Gaku0606 | 6:eff5ebc4ea13 | 426 | //beta = 1.0; |
Gaku0606 | 5:1e6fecaea25e | 427 | //if(deltaA > 0.3) beta = 0.0; |
Gaku0606 | 0:c160cac4c370 | 428 | // Apply feedback step |
Gaku0606 | 0:c160cac4c370 | 429 | qDot1 -= beta * s0; |
Gaku0606 | 0:c160cac4c370 | 430 | qDot2 -= beta * s1; |
Gaku0606 | 0:c160cac4c370 | 431 | qDot3 -= beta * s2; |
Gaku0606 | 0:c160cac4c370 | 432 | qDot4 -= beta * s3; |
Gaku0606 | 0:c160cac4c370 | 433 | } |
Gaku0606 | 0:c160cac4c370 | 434 | |
Gaku0606 | 0:c160cac4c370 | 435 | // Integrate rate of change of quaternion to yield quaternion |
Gaku0606 | 0:c160cac4c370 | 436 | newTime = (unsigned int)madgwickTimer.read_us(); |
Gaku0606 | 6:eff5ebc4ea13 | 437 | deltaT = (newTime - oldTime) / 1000000.0f; |
Gaku0606 | 0:c160cac4c370 | 438 | deltaT = fabs(deltaT); |
Gaku0606 | 0:c160cac4c370 | 439 | oldTime = newTime; |
aktk | 8:72c013425ecc | 440 | |
Gaku0606 | 0:c160cac4c370 | 441 | q0 += qDot1 * deltaT;//(1.0f / sampleFreq); |
Gaku0606 | 0:c160cac4c370 | 442 | q1 += qDot2 * deltaT;//(1.0f / sampleFreq); |
Gaku0606 | 0:c160cac4c370 | 443 | q2 += qDot3 * deltaT;//(1.0f / sampleFreq); |
Gaku0606 | 0:c160cac4c370 | 444 | q3 += qDot4 * deltaT;//(1.0f / sampleFreq); |
Gaku0606 | 0:c160cac4c370 | 445 | |
Gaku0606 | 0:c160cac4c370 | 446 | // Normalise quaternion |
Gaku0606 | 6:eff5ebc4ea13 | 447 | recipNorm = 1.0f / sqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); |
Gaku0606 | 0:c160cac4c370 | 448 | q0 *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 449 | q1 *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 450 | q2 *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 451 | q3 *= recipNorm; |
aktk | 8:72c013425ecc | 452 | |
Gaku0606 | 0:c160cac4c370 | 453 | q.w = q0; |
Gaku0606 | 0:c160cac4c370 | 454 | q.x = q1; |
Gaku0606 | 0:c160cac4c370 | 455 | q.y = q2; |
Gaku0606 | 0:c160cac4c370 | 456 | q.z = q3; |
Gaku0606 | 0:c160cac4c370 | 457 | } |
Gaku0606 | 0:c160cac4c370 | 458 | |
aktk | 8:72c013425ecc | 459 | //--------------------------------------------------------------------------------------------------- |
aktk | 8:72c013425ecc | 460 | // IMU algorithm update |
Gaku0606 | 7:c20656d96585 | 461 | |
aktk | 8:72c013425ecc | 462 | inline void MadgwickFilter::MadgwickAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az) |
aktk | 8:72c013425ecc | 463 | { |
Gaku0606 | 7:c20656d96585 | 464 | // Rate of change of quaternion from gyroscope |
Gaku0606 | 7:c20656d96585 | 465 | qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); |
Gaku0606 | 7:c20656d96585 | 466 | qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); |
Gaku0606 | 7:c20656d96585 | 467 | qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); |
Gaku0606 | 7:c20656d96585 | 468 | qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); |
Gaku0606 | 7:c20656d96585 | 469 | |
Gaku0606 | 7:c20656d96585 | 470 | // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) |
Gaku0606 | 7:c20656d96585 | 471 | if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { |
Gaku0606 | 7:c20656d96585 | 472 | |
Gaku0606 | 7:c20656d96585 | 473 | // Normalise accelerometer measurement |
Gaku0606 | 7:c20656d96585 | 474 | acc_norm = sqrt(ax * ax + ay * ay + az * az); |
Gaku0606 | 7:c20656d96585 | 475 | recipNorm = 1.0f / acc_norm; |
Gaku0606 | 7:c20656d96585 | 476 | ax *= recipNorm; |
Gaku0606 | 7:c20656d96585 | 477 | ay *= recipNorm; |
aktk | 8:72c013425ecc | 478 | az *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 479 | |
Gaku0606 | 0:c160cac4c370 | 480 | // Auxiliary variables to avoid repeated arithmetic |
Gaku0606 | 0:c160cac4c370 | 481 | _2q0 = 2.0f * q0; |
Gaku0606 | 0:c160cac4c370 | 482 | _2q1 = 2.0f * q1; |
Gaku0606 | 0:c160cac4c370 | 483 | _2q2 = 2.0f * q2; |
Gaku0606 | 0:c160cac4c370 | 484 | _2q3 = 2.0f * q3; |
Gaku0606 | 0:c160cac4c370 | 485 | _4q0 = 4.0f * q0; |
Gaku0606 | 0:c160cac4c370 | 486 | _4q1 = 4.0f * q1; |
Gaku0606 | 0:c160cac4c370 | 487 | _4q2 = 4.0f * q2; |
Gaku0606 | 0:c160cac4c370 | 488 | _8q1 = 8.0f * q1; |
Gaku0606 | 0:c160cac4c370 | 489 | _8q2 = 8.0f * q2; |
Gaku0606 | 0:c160cac4c370 | 490 | q0q0 = q0 * q0; |
Gaku0606 | 0:c160cac4c370 | 491 | q1q1 = q1 * q1; |
Gaku0606 | 0:c160cac4c370 | 492 | q2q2 = q2 * q2; |
Gaku0606 | 0:c160cac4c370 | 493 | q3q3 = q3 * q3; |
Gaku0606 | 0:c160cac4c370 | 494 | |
Gaku0606 | 0:c160cac4c370 | 495 | // Gradient decent algorithm corrective step |
aktk | 8:72c013425ecc | 496 | s0 = _4q0* q2q2 + _2q2 * ax + _4q0 * q1q1 - _2q1 * ay; |
Gaku0606 | 0:c160cac4c370 | 497 | s1 = _4q1 * q3q3 - _2q3 * ax + 4.0f * q0q0 * q1 - _2q0 * ay - _4q1 + _8q1 * q1q1 + _8q1 * q2q2 + _4q1 * az; |
Gaku0606 | 0:c160cac4c370 | 498 | s2 = 4.0f * q0q0 * q2 + _2q0 * ax + _4q2 * q3q3 - _2q3 * ay - _4q2 + _8q2 * q1q1 + _8q2 * q2q2 + _4q2 * az; |
Gaku0606 | 0:c160cac4c370 | 499 | s3 = 4.0f * q1q1 * q3 - _2q1 * ax + 4.0f * q2q2 * q3 - _2q2 * ay; |
Gaku0606 | 6:eff5ebc4ea13 | 500 | recipNorm = 1.0f / sqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude |
Gaku0606 | 0:c160cac4c370 | 501 | s0 *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 502 | s1 *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 503 | s2 *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 504 | s3 *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 505 | |
Gaku0606 | 0:c160cac4c370 | 506 | // Apply feedback step |
aktk | 8:72c013425ecc | 507 | //static float deltaA; |
aktk | 8:72c013425ecc | 508 | //deltaA = fabs(acc_norm - 1.00f); |
Gaku0606 | 5:1e6fecaea25e | 509 | //beta = 0.5*exp(-20.0*deltaA*deltaA); |
aktk | 8:72c013425ecc | 510 | //if(deltaA > 0.3f) beta = 0.0f; |
aktk | 8:72c013425ecc | 511 | //else beta = 0.1f; |
Gaku0606 | 0:c160cac4c370 | 512 | qDot1 -= beta * s0; |
Gaku0606 | 0:c160cac4c370 | 513 | qDot2 -= beta * s1; |
Gaku0606 | 0:c160cac4c370 | 514 | qDot3 -= beta * s2; |
Gaku0606 | 0:c160cac4c370 | 515 | qDot4 -= beta * s3; |
Gaku0606 | 0:c160cac4c370 | 516 | } |
Gaku0606 | 0:c160cac4c370 | 517 | |
Gaku0606 | 0:c160cac4c370 | 518 | // Integrate rate of change of quaternion to yield quaternion |
aktk | 8:72c013425ecc | 519 | |
Gaku0606 | 0:c160cac4c370 | 520 | newTime = (unsigned int)madgwickTimer.read_us(); |
aktk | 8:72c013425ecc | 521 | deltaT = ((newTime - oldTime) % 0xFFFFFFFF) / 1000000.0f; |
Gaku0606 | 0:c160cac4c370 | 522 | oldTime = newTime; |
aktk | 8:72c013425ecc | 523 | deltaT = fabs(deltaT); |
aktk | 8:72c013425ecc | 524 | |
aktk | 8:72c013425ecc | 525 | q0 += qDot1 * deltaT; |
aktk | 8:72c013425ecc | 526 | q1 += qDot2 * deltaT; |
aktk | 8:72c013425ecc | 527 | q2 += qDot3 * deltaT; |
aktk | 8:72c013425ecc | 528 | q3 += qDot4 * deltaT; |
Gaku0606 | 0:c160cac4c370 | 529 | |
Gaku0606 | 0:c160cac4c370 | 530 | // Normalise quaternion |
Gaku0606 | 6:eff5ebc4ea13 | 531 | recipNorm = 1.0f / sqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); |
Gaku0606 | 0:c160cac4c370 | 532 | q0 *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 533 | q1 *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 534 | q2 *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 535 | q3 *= recipNorm; |
Gaku0606 | 0:c160cac4c370 | 536 | |
Gaku0606 | 0:c160cac4c370 | 537 | q.w = q0; |
Gaku0606 | 0:c160cac4c370 | 538 | q.x = q1; |
Gaku0606 | 0:c160cac4c370 | 539 | q.y = q2; |
Gaku0606 | 0:c160cac4c370 | 540 | q.z = q3; |
Gaku0606 | 0:c160cac4c370 | 541 | } |
Gaku0606 | 0:c160cac4c370 | 542 | |
Gaku0606 | 0:c160cac4c370 | 543 | |
Gaku0606 | 0:c160cac4c370 | 544 | #endif |