Madgwick Filterをライブラリ化しました.内容はオープンソースになっていたやつのほぼ同じです.
Dependencies: Quaternion
Dependents: Hybrid_main_FirstEdtion rocket_logger_sinkan2018_v1 HYBRYD2018_IZU_ROCKET Hybrid_IZU2019 ... more
Fork of MadgwickFilter by
MadgwickFilter.hpp
00001 #ifndef _MADGWICK_FILTER_HPP_ 00002 #define _MADGWICK_FILTER_HPP_ 00003 00004 #include "mbed.h" 00005 #include "Quaternion.hpp" 00006 00007 #define BETA_DEF 0.1 00008 00009 /** 00010 * @bref Madgwick Filterを用いて,角速度・加速度・地磁気データを統合し,姿勢を推定するライブラリです. 00011 * @note Quaternion.hppを利用されることをお勧めいたします. 00012 */ 00013 class MadgwickFilter{ 00014 00015 public: 00016 /** 00017 @bref マドグウィックフィルター(マッジュウィックフィルター)クラスのコンストラクタ 00018 @param B double型, この値を大きくすると重力の影響を大きく取るようになります. 00019 @note 引数無しの場合,B = 0.1fが代入されます. 00020 */ 00021 MadgwickFilter(float B = BETA_DEF); 00022 00023 public: 00024 /** 00025 @bref MadgwickFilterによって角速度・加速度・地磁気データを統合し,姿勢計算します. 00026 @param gx,gy,gz 角速度データ,[rad]に変換してから入れてください. 00027 @param ax,ay,az 加速度データ, 特に規格化は必要ありません 00028 @param mx,my,mz 地磁気データ, キャリブレーションを確実に行って下さい. 00029 @note 角速度は[rad]にしてください.この関数は出来るだけ高速に呼び出し続けた方が良いと思います. 00030 @note 外部でローパスフィルタなどをかけることをお勧めします. 00031 */ 00032 void MadgwickAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz); 00033 00034 /** 00035 @bref MadgwickFilterによって角速度・加速度・地磁気データを統合し,姿勢計算します. 00036 @param gyro 角速度データ,[rad]に変換してから入れてください. 00037 @param acc 加速度データ, 特に規格化は必要ありません 00038 @param mag 地磁気データ, キャリブレーションを確実に行って下さい. 00039 @note 角速度は[rad]にしてください.この関数は出来るだけ高速に呼び出し続けた方が良いと思います. 00040 @note 外部でローパスフィルタなどをかけることをお勧めします. 00041 */ 00042 void MadgwickAHRSupdate(float *gyro, float *acc, float *mag); 00043 00044 /** 00045 @bref MadgwickFilterを角速度と加速度のみで動かし,姿勢計算を更新します. 00046 @param gx,gy,gz 角速度データ,[rad]に変換してから入れてください. 00047 @param ax,ay,az 加速度データ, 特に規格化は必要ありません 00048 @note 通常の関数でも,地磁気成分を0.0にすればこの関数が呼ばれます. 00049 */ 00050 void MadgwickAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az); 00051 00052 /** 00053 @bref 姿勢を四元数で取得します. 00054 @param Q クォータニオンクラスのインスタンスアドレス, w・i・j・kを更新します. 00055 @note unityに入れる際は軸方向を修正してください. 00056 */ 00057 void getAttitude(Quaternion *Q); 00058 00059 /** 00060 @bref 姿勢を四元数で取得します. 00061 @param _q0 実部w, double型, アドレス 00062 @param _q1 虚部i, double型, アドレス 00063 @param _q2 虚部j, double型, アドレス 00064 @param _q3 虚部k, double型, アドレス 00065 @note unityに入れる際は軸方向を修正してください. 00066 */ 00067 void getAttitude(float *_q0, float *_q1, float *_q2, float *_q3); 00068 00069 /** 00070 @bref オイラー角で姿勢を取得します. 00071 @param val ロール,ピッチ,ヨーの順に配列に格納します.3つ以上の要素の配列を入れてください. 00072 @note 値は[rad]です.[degree]に変換が必要な場合は別途計算して下さい. 00073 */ 00074 void getEulerAngle(float *val); 00075 public: 00076 Timer madgwickTimer; 00077 Quaternion q; 00078 float q0,q1,q2,q3; 00079 float beta; 00080 }; 00081 00082 MadgwickFilter::MadgwickFilter(float B){ 00083 q.w = 1.0f; 00084 q.x = 0.0f; 00085 q.y = 0.0f; 00086 q.z = 0.0f; 00087 beta = B; 00088 q0 = 1.0f; 00089 q1 = 0.0f; 00090 q2 = 0.0f; 00091 q3 = 0.0f; 00092 madgwickTimer.start(); 00093 } 00094 00095 void MadgwickFilter::getAttitude(Quaternion *Q){ 00096 *Q = q; 00097 return; 00098 } 00099 00100 00101 00102 void MadgwickFilter::getAttitude(float *_q0, float *_q1, float *_q2, float *_q3){ 00103 *_q0 = q0; 00104 *_q1 = q1; 00105 *_q2 = q2; 00106 *_q3 = q3; 00107 return; 00108 } 00109 00110 00111 void MadgwickFilter::getEulerAngle(float *val){ 00112 float q0q0 = q0 * q0, q1q1q2q2 = q1 * q1 - q2 * q2, q3q3 = q3 * q3; 00113 val[0] = (atan2(2.0f * (q0 * q1 + q2 * q3), q0q0 - q1q1q2q2 + q3q3)); 00114 val[1] = (-asin(2.0f * (q1 * q3 - q0 * q2))); 00115 val[2] = (atan2(2.0f * (q1 * q2 + q0 * q3), q0q0 + q1q1q2q2 - q3q3)); 00116 } 00117 //--------------------------------------------------------------------------------------------------- 00118 // AHRS algorithm update 00119 00120 inline void MadgwickFilter::MadgwickAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz) { 00121 00122 static float acc_norm; 00123 static float deltaT = 0.0f; 00124 static unsigned int newTime = 0, oldTime = 0; 00125 static float recipNorm; 00126 static float s0, s1, s2, s3; 00127 static float qDot1, qDot2, qDot3, qDot4; 00128 static float hx, hy; 00129 static 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; 00130 00131 // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation) 00132 if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { 00133 MadgwickAHRSupdateIMU(gx, gy, gz, ax, ay, az); 00134 return; 00135 } 00136 00137 // Rate of change of quaternion from gyroscope 00138 qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); 00139 qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); 00140 qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); 00141 qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); 00142 00143 // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) 00144 if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { 00145 00146 // Normalise accelerometer measurement 00147 acc_norm = sqrt(ax * ax + ay * ay + az * az); 00148 recipNorm = 1.0f / acc_norm; 00149 ax *= recipNorm; 00150 ay *= recipNorm; 00151 az *= recipNorm; 00152 00153 // Normalise magnetometer measurement 00154 recipNorm = 1.0f / sqrt(mx * mx + my * my + mz * mz); 00155 mx *= recipNorm; 00156 my *= recipNorm; 00157 mz *= recipNorm; 00158 00159 // Auxiliary variables to avoid repeated arithmetic 00160 _2q0mx = 2.0f * q0 * mx; 00161 _2q0my = 2.0f * q0 * my; 00162 _2q0mz = 2.0f * q0 * mz; 00163 _2q1mx = 2.0f * q1 * mx; 00164 _2q0 = 2.0f * q0; 00165 _2q1 = 2.0f * q1; 00166 _2q2 = 2.0f * q2; 00167 _2q3 = 2.0f * q3; 00168 _2q0q2 = 2.0f * q0 * q2; 00169 _2q2q3 = 2.0f * q2 * q3; 00170 q0q0 = q0 * q0; 00171 q0q1 = q0 * q1; 00172 q0q2 = q0 * q2; 00173 q0q3 = q0 * q3; 00174 q1q1 = q1 * q1; 00175 q1q2 = q1 * q2; 00176 q1q3 = q1 * q3; 00177 q2q2 = q2 * q2; 00178 q2q3 = q2 * q3; 00179 q3q3 = q3 * q3; 00180 00181 // Reference direction of Earth's magnetic field 00182 hx = mx * q0q0 - _2q0my * q3 + _2q0mz * q2 + mx * q1q1 + _2q1 * my * q2 + _2q1 * mz * q3 - mx * q2q2 - mx * q3q3; 00183 hy = _2q0mx * q3 + my * q0q0 - _2q0mz * q1 + _2q1mx * q2 - my * q1q1 + my * q2q2 + _2q2 * mz * q3 - my * q3q3; 00184 _2bx = sqrt(hx * hx + hy * hy); 00185 _2bz = -_2q0mx * q2 + _2q0my * q1 + mz * q0q0 + _2q1mx * q3 - mz * q1q1 + _2q2 * my * q3 - mz * q2q2 + mz * q3q3; 00186 _4bx = 2.0f * _2bx; 00187 _4bz = 2.0f * _2bz; 00188 00189 // Gradient decent algorithm corrective step 00190 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); 00191 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); 00192 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); 00193 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); 00194 recipNorm = 1.0f / sqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude 00195 s0 *= recipNorm; 00196 s1 *= recipNorm; 00197 s2 *= recipNorm; 00198 s3 *= recipNorm; 00199 00200 float deltaA = fabs(acc_norm - 1.00f); 00201 //beta = 0.1*exp(-1.0*deltaA*deltaA); 00202 //beta = 0.3*exp(-20.0*deltaA*deltaA); 00203 //beta = beta*exp(-30.0f*deltaA*deltaA); 00204 //printf("%f\r\n", beta); 00205 //beta = 1.0; 00206 //if(deltaA > 0.3) beta = 0.0; 00207 // Apply feedback step 00208 qDot1 -= beta * s0; 00209 qDot2 -= beta * s1; 00210 qDot3 -= beta * s2; 00211 qDot4 -= beta * s3; 00212 } 00213 00214 // Integrate rate of change of quaternion to yield quaternion 00215 newTime = (unsigned int)madgwickTimer.read_us(); 00216 deltaT = (newTime - oldTime) / 1000000.0f; 00217 deltaT = fabs(deltaT); 00218 oldTime = newTime; 00219 00220 q0 += qDot1 * deltaT;//(1.0f / sampleFreq); 00221 q1 += qDot2 * deltaT;//(1.0f / sampleFreq); 00222 q2 += qDot3 * deltaT;//(1.0f / sampleFreq); 00223 q3 += qDot4 * deltaT;//(1.0f / sampleFreq); 00224 00225 // Normalise quaternion 00226 recipNorm = 1.0f / sqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); 00227 q0 *= recipNorm; 00228 q1 *= recipNorm; 00229 q2 *= recipNorm; 00230 q3 *= recipNorm; 00231 00232 q.w = q0; 00233 q.x = q1; 00234 q.y = q2; 00235 q.z = q3; 00236 } 00237 00238 inline void MadgwickFilter::MadgwickAHRSupdate(float *gyro, float *acc, float *mag){ 00239 00240 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; 00241 static float acc_norm; 00242 static float deltaT = 0.0f; 00243 static unsigned int newTime = 0, oldTime = 0; 00244 static float recipNorm; 00245 static float s0, s1, s2, s3; 00246 static float qDot1, qDot2, qDot3, qDot4; 00247 static float hx, hy; 00248 static 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; 00249 00250 gx = gyro[0]; 00251 gy = gyro[1]; 00252 gz = gyro[2]; 00253 ax = acc[0]; 00254 ay = acc[1]; 00255 az = acc[2]; 00256 mx = mag[0]; 00257 my = mag[1]; 00258 mz = mag[2]; 00259 00260 // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation) 00261 if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { 00262 MadgwickAHRSupdateIMU(gx, gy, gz, ax, ay, az); 00263 return; 00264 } 00265 00266 // Rate of change of quaternion from gyroscope 00267 qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); 00268 qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); 00269 qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); 00270 qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); 00271 00272 // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) 00273 if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { 00274 00275 // Normalise accelerometer measurement 00276 acc_norm = sqrt(ax * ax + ay * ay + az * az); 00277 recipNorm = 1.0f / acc_norm; 00278 ax *= recipNorm; 00279 ay *= recipNorm; 00280 az *= recipNorm; 00281 00282 // Normalise magnetometer measurement 00283 recipNorm = 1.0f / sqrt(mx * mx + my * my + mz * mz); 00284 mx *= recipNorm; 00285 my *= recipNorm; 00286 mz *= recipNorm; 00287 00288 // Auxiliary variables to avoid repeated arithmetic 00289 _2q0mx = 2.0f * q0 * mx; 00290 _2q0my = 2.0f * q0 * my; 00291 _2q0mz = 2.0f * q0 * mz; 00292 _2q1mx = 2.0f * q1 * mx; 00293 _2q0 = 2.0f * q0; 00294 _2q1 = 2.0f * q1; 00295 _2q2 = 2.0f * q2; 00296 _2q3 = 2.0f * q3; 00297 _2q0q2 = 2.0f * q0 * q2; 00298 _2q2q3 = 2.0f * q2 * q3; 00299 q0q0 = q0 * q0; 00300 q0q1 = q0 * q1; 00301 q0q2 = q0 * q2; 00302 q0q3 = q0 * q3; 00303 q1q1 = q1 * q1; 00304 q1q2 = q1 * q2; 00305 q1q3 = q1 * q3; 00306 q2q2 = q2 * q2; 00307 q2q3 = q2 * q3; 00308 q3q3 = q3 * q3; 00309 00310 // Reference direction of Earth's magnetic field 00311 hx = mx * q0q0 - _2q0my * q3 + _2q0mz * q2 + mx * q1q1 + _2q1 * my * q2 + _2q1 * mz * q3 - mx * q2q2 - mx * q3q3; 00312 hy = _2q0mx * q3 + my * q0q0 - _2q0mz * q1 + _2q1mx * q2 - my * q1q1 + my * q2q2 + _2q2 * mz * q3 - my * q3q3; 00313 _2bx = sqrt(hx * hx + hy * hy); 00314 _2bz = -_2q0mx * q2 + _2q0my * q1 + mz * q0q0 + _2q1mx * q3 - mz * q1q1 + _2q2 * my * q3 - mz * q2q2 + mz * q3q3; 00315 _4bx = 2.0f * _2bx; 00316 _4bz = 2.0f * _2bz; 00317 00318 // Gradient decent algorithm corrective step 00319 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); 00320 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); 00321 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); 00322 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); 00323 recipNorm = 1.0f / sqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude 00324 s0 *= recipNorm; 00325 s1 *= recipNorm; 00326 s2 *= recipNorm; 00327 s3 *= recipNorm; 00328 00329 float deltaA = fabs(acc_norm - 1.00f); 00330 //beta = 0.1*exp(-1.0*deltaA*deltaA); 00331 //beta = 0.3*exp(-20.0*deltaA*deltaA); 00332 //beta = beta*exp(-30.0f*deltaA*deltaA); 00333 //printf("%f\r\n", beta); 00334 //beta = 1.0; 00335 //if(deltaA > 0.3) beta = 0.0; 00336 // Apply feedback step 00337 qDot1 -= beta * s0; 00338 qDot2 -= beta * s1; 00339 qDot3 -= beta * s2; 00340 qDot4 -= beta * s3; 00341 } 00342 00343 // Integrate rate of change of quaternion to yield quaternion 00344 newTime = (unsigned int)madgwickTimer.read_us(); 00345 deltaT = (newTime - oldTime) / 1000000.0f; 00346 deltaT = fabs(deltaT); 00347 oldTime = newTime; 00348 00349 q0 += qDot1 * deltaT;//(1.0f / sampleFreq); 00350 q1 += qDot2 * deltaT;//(1.0f / sampleFreq); 00351 q2 += qDot3 * deltaT;//(1.0f / sampleFreq); 00352 q3 += qDot4 * deltaT;//(1.0f / sampleFreq); 00353 00354 // Normalise quaternion 00355 recipNorm = 1.0f / sqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); 00356 q0 *= recipNorm; 00357 q1 *= recipNorm; 00358 q2 *= recipNorm; 00359 q3 *= recipNorm; 00360 00361 q.w = q0; 00362 q.x = q1; 00363 q.y = q2; 00364 q.z = q3; 00365 } 00366 00367 //--------------------------------------------------------------------------------------------------- 00368 // IMU algorithm update 00369 00370 inline void MadgwickFilter::MadgwickAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az) { 00371 static float deltaT = 0; 00372 static unsigned int newTime = 0, oldTime = 0; 00373 static float recipNorm; 00374 static float s0, s1, s2, s3; 00375 static float qDot1, qDot2, qDot3, qDot4; 00376 static float _2q0, _2q1, _2q2, _2q3, _4q0, _4q1, _4q2 ,_8q1, _8q2, q0q0, q1q1, q2q2, q3q3; 00377 static float acc_norm; 00378 00379 // Rate of change of quaternion from gyroscope 00380 qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); 00381 qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); 00382 qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); 00383 qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); 00384 00385 // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) 00386 if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { 00387 00388 // Normalise accelerometer measurement 00389 acc_norm = sqrt(ax * ax + ay * ay + az * az); 00390 recipNorm = 1.0f / acc_norm; 00391 ax *= recipNorm; 00392 ay *= recipNorm; 00393 az *= recipNorm; 00394 00395 // Auxiliary variables to avoid repeated arithmetic 00396 _2q0 = 2.0f * q0; 00397 _2q1 = 2.0f * q1; 00398 _2q2 = 2.0f * q2; 00399 _2q3 = 2.0f * q3; 00400 _4q0 = 4.0f * q0; 00401 _4q1 = 4.0f * q1; 00402 _4q2 = 4.0f * q2; 00403 _8q1 = 8.0f * q1; 00404 _8q2 = 8.0f * q2; 00405 q0q0 = q0 * q0; 00406 q1q1 = q1 * q1; 00407 q2q2 = q2 * q2; 00408 q3q3 = q3 * q3; 00409 00410 // Gradient decent algorithm corrective step 00411 s0 = _4q0 * q2q2 + _2q2 * ax + _4q0 * q1q1 - _2q1 * ay; 00412 s1 = _4q1 * q3q3 - _2q3 * ax + 4.0f * q0q0 * q1 - _2q0 * ay - _4q1 + _8q1 * q1q1 + _8q1 * q2q2 + _4q1 * az; 00413 s2 = 4.0f * q0q0 * q2 + _2q0 * ax + _4q2 * q3q3 - _2q3 * ay - _4q2 + _8q2 * q1q1 + _8q2 * q2q2 + _4q2 * az; 00414 s3 = 4.0f * q1q1 * q3 - _2q1 * ax + 4.0f * q2q2 * q3 - _2q2 * ay; 00415 recipNorm = 1.0f / sqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude 00416 s0 *= recipNorm; 00417 s1 *= recipNorm; 00418 s2 *= recipNorm; 00419 s3 *= recipNorm; 00420 00421 // Apply feedback step 00422 static float deltaA; 00423 deltaA = fabs(acc_norm - 1.00f); 00424 //beta = 0.5*exp(-20.0*deltaA*deltaA); 00425 if(deltaA > 0.3f) beta = 0.0f; 00426 else beta = 0.1f; 00427 qDot1 -= beta * s0; 00428 qDot2 -= beta * s1; 00429 qDot3 -= beta * s2; 00430 qDot4 -= beta * s3; 00431 } 00432 00433 // Integrate rate of change of quaternion to yield quaternion 00434 newTime = (unsigned int)madgwickTimer.read_us(); 00435 deltaT = (newTime - oldTime) / 1000000.0f; 00436 deltaT = fabs(deltaT); 00437 oldTime = newTime; 00438 q0 += qDot1 * deltaT;; 00439 q1 += qDot2 * deltaT;; 00440 q2 += qDot3 * deltaT;; 00441 q3 += qDot4 * deltaT;; 00442 00443 // Normalise quaternion 00444 recipNorm = 1.0f / sqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); 00445 q0 *= recipNorm; 00446 q1 *= recipNorm; 00447 q2 *= recipNorm; 00448 q3 *= recipNorm; 00449 00450 q.w = q0; 00451 q.x = q1; 00452 q.y = q2; 00453 q.z = q3; 00454 } 00455 00456 00457 #endif
Generated on Tue Jul 12 2022 18:24:13 by 1.7.2