From 1f4516c92a47f81808fd147e95e0a74e3afe9867 Mon Sep 17 00:00:00 2001 From: qqqlab <46283638+qqqlab@users.noreply.github.com> Date: Fri, 12 Jul 2024 23:36:19 +0200 Subject: [PATCH] . --- src/madflight/ahrs/Madgwick/madgwick.h | 403 ------------------------- src/madflight/ahrs/Mahony/mahony.h | 208 ------------- 2 files changed, 611 deletions(-) delete mode 100644 src/madflight/ahrs/Madgwick/madgwick.h delete mode 100644 src/madflight/ahrs/Mahony/mahony.h diff --git a/src/madflight/ahrs/Madgwick/madgwick.h b/src/madflight/ahrs/Madgwick/madgwick.h deleted file mode 100644 index b7d2cbb..0000000 --- a/src/madflight/ahrs/Madgwick/madgwick.h +++ /dev/null @@ -1,403 +0,0 @@ -//============================================================================================================== -// Madgwick -//============================================================================================================== - -static const float ahrs_MadgwickB = 0.041; //Madgwick filter parameter - -//NED reference frame -//gyro in rad/sec -//acc in g -//mag any unit of measurement - -//Initialize quaternion for Madgwick filter -float q0 = 1.0f; -float q1 = 0.0f; -float q2 = 0.0f; -float q3 = 0.0f; - -void _ahrs_Madgwick9DOF(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float dt); -void _ahrs_Madgwick6DOF(float gx, float gy, float gz, float ax, float ay, float az, float dt); - -void ahrs_Madgwick(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float dt) { - //Use 6DOF algorithm if magnetometer measurement invalid or unavailable (avoids NaN in magnetometer normalisation) - if( (mx == 0.0f) && (my == 0.0f) && (mz == 0.0f) ) { - _ahrs_Madgwick6DOF(gx, gy, gz, ax, ay, az, dt); - }else{ - _ahrs_Madgwick9DOF(gx, gy, gz, ax, ay, az, mx, my, mz, dt); - } -} - -void _ahrs_Madgwick9DOF(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float dt) { - //DESCRIPTION: Attitude estimation through sensor fusion - 9DOF - /* - * This function fuses the accelerometer gyro, and magnetometer readings AccX, AccY, AccZ, GyroX, GyroY, GyroZ, MagX, MagY, and MagZ for attitude estimation. - * Don't worry about the math. There is a tunable parameter ahrs_MadgwickB in the user specified variable section which basically - * adjusts the weight of gyro data in the state estimate. Higher beta leads to noisier estimate, lower - * beta leads to slower to respond estimate. It is currently tuned for 2kHz loop rate. This function updates the ahrs_roll, - * ahrs_pitch, and ahrs_yaw variables which are in degrees. - */ - float recipNorm; - float s0, s1, s2, s3; - float qDot1, qDot2, qDot3, qDot4; - float hx, hy; - 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; - - //Rate of change of quaternion from gyroscope - qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); - qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); - qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); - qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); - - //Compute feedback only if accelerometer measurement is in range 0.9g - 1.1g - float alen2 = ax * ax + ay * ay + az * az; - if (0.81 <= alen2 && alen2 <= 1.21) { - - //Normalise accelerometer measurement - recipNorm = 1.0/sqrtf(alen2); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; - - //Normalise magnetometer measurement - recipNorm = 1.0/sqrtf(mx * mx + my * my + mz * mz); - mx *= recipNorm; - my *= recipNorm; - mz *= recipNorm; - - //Auxiliary variables to avoid repeated arithmetic - _2q0mx = 2.0f * q0 * mx; - _2q0my = 2.0f * q0 * my; - _2q0mz = 2.0f * q0 * mz; - _2q1mx = 2.0f * q1 * mx; - _2q0 = 2.0f * q0; - _2q1 = 2.0f * q1; - _2q2 = 2.0f * q2; - _2q3 = 2.0f * q3; - _2q0q2 = 2.0f * q0 * q2; - _2q2q3 = 2.0f * q2 * q3; - q0q0 = q0 * q0; - q0q1 = q0 * q1; - q0q2 = q0 * q2; - q0q3 = q0 * q3; - q1q1 = q1 * q1; - q1q2 = q1 * q2; - q1q3 = q1 * q3; - q2q2 = q2 * q2; - q2q3 = q2 * q3; - q3q3 = q3 * q3; - - //Reference direction of Earth's magnetic field - hx = mx * q0q0 - _2q0my * q3 + _2q0mz * q2 + mx * q1q1 + _2q1 * my * q2 + _2q1 * mz * q3 - mx * q2q2 - mx * q3q3; - hy = _2q0mx * q3 + my * q0q0 - _2q0mz * q1 + _2q1mx * q2 - my * q1q1 + my * q2q2 + _2q2 * mz * q3 - my * q3q3; - _2bx = sqrtf(hx * hx + hy * hy); - _2bz = -_2q0mx * q2 + _2q0my * q1 + mz * q0q0 + _2q1mx * q3 - mz * q1q1 + _2q2 * my * q3 - mz * q2q2 + mz * q3q3; - _4bx = 2.0f * _2bx; - _4bz = 2.0f * _2bz; - - //Gradient decent algorithm corrective step - 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); - 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); - 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); - 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); - recipNorm = 1.0/sqrtf(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude - s0 *= recipNorm; - s1 *= recipNorm; - s2 *= recipNorm; - s3 *= recipNorm; - - //Apply feedback step - qDot1 -= ahrs_MadgwickB * s0; - qDot2 -= ahrs_MadgwickB * s1; - qDot3 -= ahrs_MadgwickB * s2; - qDot4 -= ahrs_MadgwickB * s3; - } - - //Integrate rate of change of quaternion to yield quaternion - q0 += qDot1 * dt; - q1 += qDot2 * dt; - q2 += qDot3 * dt; - q3 += qDot4 * dt; - - //Normalize quaternion - recipNorm = 1.0/sqrtf(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); - q0 *= recipNorm; - q1 *= recipNorm; - q2 *= recipNorm; - q3 *= recipNorm; -} - -void _ahrs_Madgwick6DOF(float gx, float gy, float gz, float ax, float ay, float az, float dt) { - //DESCRIPTION: Attitude estimation through sensor fusion - 6DOF - /* - * See description of ahrs_Madgwick() for more information. This is a 6DOF implimentation for when magnetometer data is not - * available (for example when using the recommended MPU6050 IMU for the default setup). - */ - float recipNorm; - float s0, s1, s2, s3; - float qDot1, qDot2, qDot3, qDot4; - float _2q0, _2q1, _2q2, _2q3, _4q0, _4q1, _4q2 ,_8q1, _8q2, q0q0, q1q1, q2q2, q3q3; - - //Convert gyroscope degrees/sec to radians/sec - gx *= 0.0174533f; - gy *= 0.0174533f; - gz *= 0.0174533f; - - //Rate of change of quaternion from gyroscope - qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); - qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); - qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); - qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); - - //Compute feedback only if accelerometer measurement is in range 0.9g - 1.1g - float alen2 = ax * ax + ay * ay + az * az; - if (0.81 <= alen2 && alen2 <= 1.21) { - - //Normalise accelerometer measurement - recipNorm = 1.0/sqrtf(alen2); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; - - //Auxiliary variables to avoid repeated arithmetic - _2q0 = 2.0f * q0; - _2q1 = 2.0f * q1; - _2q2 = 2.0f * q2; - _2q3 = 2.0f * q3; - _4q0 = 4.0f * q0; - _4q1 = 4.0f * q1; - _4q2 = 4.0f * q2; - _8q1 = 8.0f * q1; - _8q2 = 8.0f * q2; - q0q0 = q0 * q0; - q1q1 = q1 * q1; - q2q2 = q2 * q2; - q3q3 = q3 * q3; - - //Gradient decent algorithm corrective step - s0 = _4q0 * q2q2 + _2q2 * ax + _4q0 * q1q1 - _2q1 * ay; - s1 = _4q1 * q3q3 - _2q3 * ax + 4.0f * q0q0 * q1 - _2q0 * ay - _4q1 + _8q1 * q1q1 + _8q1 * q2q2 + _4q1 * az; - s2 = 4.0f * q0q0 * q2 + _2q0 * ax + _4q2 * q3q3 - _2q3 * ay - _4q2 + _8q2 * q1q1 + _8q2 * q2q2 + _4q2 * az; - s3 = 4.0f * q1q1 * q3 - _2q1 * ax + 4.0f * q2q2 * q3 - _2q2 * ay; - recipNorm = 1.0/sqrtf(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); //normalise step magnitude - s0 *= recipNorm; - s1 *= recipNorm; - s2 *= recipNorm; - s3 *= recipNorm; - - //Apply feedback step - qDot1 -= ahrs_MadgwickB * s0; - qDot2 -= ahrs_MadgwickB * s1; - qDot3 -= ahrs_MadgwickB * s2; - qDot4 -= ahrs_MadgwickB * s3; - } - - //Integrate rate of change of quaternion to yield quaternion - q0 += qDot1 * dt; - q1 += qDot2 * dt; - q2 += qDot3 * dt; - q3 += qDot4 * dt; - - //Normalise quaternion - recipNorm = 1.0/sqrtf(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); - q0 *= recipNorm; - q1 *= recipNorm; - q2 *= recipNorm; - q3 *= recipNorm; -} - -//============================================================================================================== -// Mahony -//============================================================================================================== -//source: https://github.com/PaulStoffregen/MahonyAHRS - -extern float ahrs_Mahony2KP; // 2 * proportional gain (Kp) -extern float ahrs_Mahony2KI; // 2 * integral gain (Ki) -//float q0, q1, q2, q3; // quaternion of sensor frame relative to auxiliary frame (defined above) -float integralFBx = 0, integralFBy = 0, integralFBz = 0; // integral error terms scaled by Ki - -void _ahrs_Mahony9DOF(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float dt); -void _ahrs_Mahony6DOF(float gx, float gy, float gz, float ax, float ay, float az, float dt); - -void ahrs_Mahony(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float dt) { - //Use 6DOF algorithm if magnetometer measurement invalid or unavailable (avoids NaN in magnetometer normalisation) - if( (mx == 0.0f) && (my == 0.0f) && (mz == 0.0f) ) { - _ahrs_Mahony6DOF(gx, gy, gz, ax, ay, az, dt); - }else{ - _ahrs_Mahony9DOF(gx, gy, gz, ax, ay, az, mx, my, mz, dt); - } -} - -void _ahrs_Mahony9DOF(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float dt) { - float recipNorm; - float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; - float hx, hy, bx, bz; - float halfvx, halfvy, halfvz, halfwx, halfwy, halfwz; - float halfex, halfey, halfez; - float qa, qb, qc; - - // Convert gyroscope degrees/sec to radians/sec - gx *= 0.0174533f; - gy *= 0.0174533f; - gz *= 0.0174533f; - - //Compute feedback only if accelerometer measurement is in range 0.9g - 1.1g - float alen2 = ax * ax + ay * ay + az * az; - if (0.81 <= alen2 && alen2 <= 1.21) { - - //Normalise accelerometer measurement - recipNorm = 1.0/sqrtf(alen2); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; - - // Normalise magnetometer measurement - recipNorm = 1.0f/sqrtf(mx * mx + my * my + mz * mz); - mx *= recipNorm; - my *= recipNorm; - mz *= recipNorm; - - // Auxiliary variables to avoid repeated arithmetic - q0q0 = q0 * q0; - q0q1 = q0 * q1; - q0q2 = q0 * q2; - q0q3 = q0 * q3; - q1q1 = q1 * q1; - q1q2 = q1 * q2; - q1q3 = q1 * q3; - q2q2 = q2 * q2; - q2q3 = q2 * q3; - q3q3 = q3 * q3; - - // Reference direction of Earth's magnetic field - hx = 2.0f * (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2)); - hy = 2.0f * (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1)); - bx = sqrtf(hx * hx + hy * hy); - bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2)); - - // Estimated direction of gravity and magnetic field - halfvx = q1q3 - q0q2; - halfvy = q0q1 + q2q3; - halfvz = q0q0 - 0.5f + q3q3; - halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2); - halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3); - halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2); - - // Error is sum of cross product between estimated direction - // and measured direction of field vectors - halfex = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy); - halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz); - halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx); - - // Compute and apply integral feedback if enabled - if(ahrs_Mahony2KI > 0.0f) { - // integral error scaled by Ki - integralFBx += ahrs_Mahony2KI * halfex * dt; - integralFBy += ahrs_Mahony2KI * halfey * dt; - integralFBz += ahrs_Mahony2KI * halfez * dt; - gx += integralFBx; // apply integral feedback - gy += integralFBy; - gz += integralFBz; - } else { - integralFBx = 0.0f; // prevent integral windup - integralFBy = 0.0f; - integralFBz = 0.0f; - } - - // Apply proportional feedback - gx += ahrs_Mahony2KP * halfex; - gy += ahrs_Mahony2KP * halfey; - gz += ahrs_Mahony2KP * halfez; - } - - // Integrate rate of change of quaternion - gx *= 0.5f * dt; // pre-multiply common factors - gy *= 0.5f * dt; - gz *= 0.5f * dt; - qa = q0; - qb = q1; - qc = q2; - q0 += (-qb * gx - qc * gy - q3 * gz); - q1 += (qa * gx + qc * gz - q3 * gy); - q2 += (qa * gy - qb * gz + q3 * gx); - q3 += (qa * gz + qb * gy - qc * gx); - - // Normalise quaternion - recipNorm = 1.0f/sqrtf(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); - q0 *= recipNorm; - q1 *= recipNorm; - q2 *= recipNorm; - q3 *= recipNorm; -} - -void _ahrs_Mahony6DOF(float gx, float gy, float gz, float ax, float ay, float az, float dt) { - float recipNorm; - float halfvx, halfvy, halfvz; - float halfex, halfey, halfez; - float qa, qb, qc; - - // Convert gyroscope degrees/sec to radians/sec - gx *= 0.0174533f; - gy *= 0.0174533f; - gz *= 0.0174533f; - - //Compute feedback only if accelerometer measurement is in range 0.9g - 1.1g - float alen2 = ax * ax + ay * ay + az * az; - if (0.81 <= alen2 && alen2 <= 1.21) { - - //Normalise accelerometer measurement - recipNorm = 1.0/sqrtf(alen2); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; - - // Estimated direction of gravity - halfvx = q1 * q3 - q0 * q2; - halfvy = q0 * q1 + q2 * q3; - halfvz = q0 * q0 - 0.5f + q3 * q3; - - // Error is sum of cross product between estimated - // and measured direction of gravity - halfex = (ay * halfvz - az * halfvy); - halfey = (az * halfvx - ax * halfvz); - halfez = (ax * halfvy - ay * halfvx); - - // Compute and apply integral feedback if enabled - if(ahrs_Mahony2KI > 0.0f) { - // integral error scaled by Ki - integralFBx += ahrs_Mahony2KI * halfex * dt; - integralFBy += ahrs_Mahony2KI * halfey * dt; - integralFBz += ahrs_Mahony2KI * halfez * dt; - gx += integralFBx; // apply integral feedback - gy += integralFBy; - gz += integralFBz; - } else { - integralFBx = 0.0f; // prevent integral windup - integralFBy = 0.0f; - integralFBz = 0.0f; - } - - // Apply proportional feedback - gx += ahrs_Mahony2KP * halfex; - gy += ahrs_Mahony2KP * halfey; - gz += ahrs_Mahony2KP * halfez; - } - - // Integrate rate of change of quaternion - gx *= 0.5f * dt; // pre-multiply common factors - gy *= 0.5f * dt; - gz *= 0.5f * dt; - qa = q0; - qb = q1; - qc = q2; - q0 += (-qb * gx - qc * gy - q3 * gz); - q1 += (qa * gx + qc * gz - q3 * gy); - q2 += (qa * gy - qb * gz + q3 * gx); - q3 += (qa * gz + qb * gy - qc * gx); - - // Normalise quaternion - recipNorm = 1.0f/sqrtf(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); - q0 *= recipNorm; - q1 *= recipNorm; - q2 *= recipNorm; - q3 *= recipNorm; -} diff --git a/src/madflight/ahrs/Mahony/mahony.h b/src/madflight/ahrs/Mahony/mahony.h deleted file mode 100644 index ebf3a2e..0000000 --- a/src/madflight/ahrs/Mahony/mahony.h +++ /dev/null @@ -1,208 +0,0 @@ -//============================================================================================================== -// Mahony -//============================================================================================================== -//source: https://github.com/PaulStoffregen/MahonyAHRS - -static const float ahrs_Mahony2KP = 2 * 0.5; //Mahony: 2 * proportional gain (Kp) -static const float ahrs_Mahony2KI = 2 * 0.0; //Mahony: 2 * integral gain (Ki) - -//NED reference frame -//gyro in rad/sec -//acc in g -//mag any unit of measurement - -// quaternion of sensor frame relative to auxiliary frame -float q0 = 1.0f; //Initialize quaternion for Madgwick filter (shared between ahrs_Madgwick6DOF and ahrs_Madgwick9DOF) -float q1 = 0.0f; -float q2 = 0.0f; -float q3 = 0.0f; - - -float integralFBx = 0, integralFBy = 0, integralFBz = 0; // integral error terms scaled by Ki - -void _ahrs_Mahony9DOF(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float dt); -void _ahrs_Mahony6DOF(float gx, float gy, float gz, float ax, float ay, float az, float dt); - -void ahrs_Mahony(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float dt) { - //Use 6DOF algorithm if magnetometer measurement invalid or unavailable (avoids NaN in magnetometer normalisation) - if( (mx == 0.0f) && (my == 0.0f) && (mz == 0.0f) ) { - _ahrs_Mahony6DOF(gx, gy, gz, ax, ay, az, dt); - }else{ - _ahrs_Mahony9DOF(gx, gy, gz, ax, ay, az, mx, my, mz, dt); - } -} - -void _ahrs_Mahony9DOF(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float dt) { - float recipNorm; - float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; - float hx, hy, bx, bz; - float halfvx, halfvy, halfvz, halfwx, halfwy, halfwz; - float halfex, halfey, halfez; - float qa, qb, qc; - - //Compute feedback only if accelerometer measurement is in range 0.9g - 1.1g - float alen2 = ax * ax + ay * ay + az * az; - -#if AHRS_USE == AHRS_USE_MAHONY_BF - if (0.81 <= alen2 && alen2 <= 1.21) { -#else - if (alen2>0) { -#endif - - //Normalise accelerometer measurement - recipNorm = 1.0/sqrtf(alen2); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; - - // Normalise magnetometer measurement - recipNorm = 1.0f/sqrtf(mx * mx + my * my + mz * mz); - mx *= recipNorm; - my *= recipNorm; - mz *= recipNorm; - - // Auxiliary variables to avoid repeated arithmetic - q0q0 = q0 * q0; - q0q1 = q0 * q1; - q0q2 = q0 * q2; - q0q3 = q0 * q3; - q1q1 = q1 * q1; - q1q2 = q1 * q2; - q1q3 = q1 * q3; - q2q2 = q2 * q2; - q2q3 = q2 * q3; - q3q3 = q3 * q3; - - // Reference direction of Earth's magnetic field - hx = 2.0f * (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2)); - hy = 2.0f * (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1)); - bx = sqrtf(hx * hx + hy * hy); - bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2)); - - // Estimated direction of gravity and magnetic field - halfvx = q1q3 - q0q2; - halfvy = q0q1 + q2q3; - halfvz = q0q0 - 0.5f + q3q3; - halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2); - halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3); - halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2); - - // Error is sum of cross product between estimated direction - // and measured direction of field vectors - halfex = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy); - halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz); - halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx); - - // Compute and apply integral feedback if enabled - if(ahrs_Mahony2KI > 0.0f) { - // integral error scaled by Ki - integralFBx += ahrs_Mahony2KI * halfex * dt; - integralFBy += ahrs_Mahony2KI * halfey * dt; - integralFBz += ahrs_Mahony2KI * halfez * dt; - gx += integralFBx; // apply integral feedback - gy += integralFBy; - gz += integralFBz; - } else { - integralFBx = 0.0f; // prevent integral windup - integralFBy = 0.0f; - integralFBz = 0.0f; - } - - // Apply proportional feedback - gx += ahrs_Mahony2KP * halfex; - gy += ahrs_Mahony2KP * halfey; - gz += ahrs_Mahony2KP * halfez; - } - - // Integrate rate of change of quaternion - gx *= 0.5f * dt; // pre-multiply common factors - gy *= 0.5f * dt; - gz *= 0.5f * dt; - qa = q0; - qb = q1; - qc = q2; - q0 += (-qb * gx - qc * gy - q3 * gz); - q1 += (qa * gx + qc * gz - q3 * gy); - q2 += (qa * gy - qb * gz + q3 * gx); - q3 += (qa * gz + qb * gy - qc * gx); - - // Normalise quaternion - recipNorm = 1.0f/sqrtf(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); - q0 *= recipNorm; - q1 *= recipNorm; - q2 *= recipNorm; - q3 *= recipNorm; -} - -void _ahrs_Mahony6DOF(float gx, float gy, float gz, float ax, float ay, float az, float dt) { - float recipNorm; - float halfvx, halfvy, halfvz; - float halfex, halfey, halfez; - float qa, qb, qc; - - //Compute feedback only if accelerometer measurement is in range 0.9g - 1.1g - float alen2 = ax * ax + ay * ay + az * az; - -#if AHRS_USE == AHRS_USE_MAHONY_BF - if (0.81 <= alen2 && alen2 <= 1.21) { -#else - if (alen2>0) { -#endif - - //Normalise accelerometer measurement - recipNorm = 1.0/sqrtf(alen2); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; - - // Estimated direction of gravity - halfvx = q1 * q3 - q0 * q2; - halfvy = q0 * q1 + q2 * q3; - halfvz = q0 * q0 - 0.5f + q3 * q3; - - // Error is sum of cross product between estimated - // and measured direction of gravity - halfex = (ay * halfvz - az * halfvy); - halfey = (az * halfvx - ax * halfvz); - halfez = (ax * halfvy - ay * halfvx); - - // Compute and apply integral feedback if enabled - if(ahrs_Mahony2KI > 0.0f) { - // integral error scaled by Ki - integralFBx += ahrs_Mahony2KI * halfex * dt; - integralFBy += ahrs_Mahony2KI * halfey * dt; - integralFBz += ahrs_Mahony2KI * halfez * dt; - gx += integralFBx; // apply integral feedback - gy += integralFBy; - gz += integralFBz; - } else { - integralFBx = 0.0f; // prevent integral windup - integralFBy = 0.0f; - integralFBz = 0.0f; - } - - // Apply proportional feedback - gx += ahrs_Mahony2KP * halfex; - gy += ahrs_Mahony2KP * halfey; - gz += ahrs_Mahony2KP * halfez; - } - - // Integrate rate of change of quaternion - gx *= 0.5f * dt; // pre-multiply common factors - gy *= 0.5f * dt; - gz *= 0.5f * dt; - qa = q0; - qb = q1; - qc = q2; - q0 += (-qb * gx - qc * gy - q3 * gz); - q1 += (qa * gx + qc * gz - q3 * gy); - q2 += (qa * gy - qb * gz + q3 * gx); - q3 += (qa * gz + qb * gy - qc * gx); - - // Normalise quaternion - recipNorm = 1.0f/sqrtf(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); - q0 *= recipNorm; - q1 *= recipNorm; - q2 *= recipNorm; - q3 *= recipNorm; -}