123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186 |
- //=============================================================================================
- // MahonyAHRS.c
- //=============================================================================================
- //
- // Madgwick's implementation of Mayhony's AHRS algorithm.
- // See: http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/
- //
- // From the x-io website "Open-source resources available on this website are
- // provided under the GNU General Public Licence unless an alternative licence
- // is provided in source."
- //
- // Date Author Notes
- // 29/09/2011 SOH Madgwick Initial release
- // 02/10/2011 SOH Madgwick Optimised for reduced CPU load
- //
- // Algorithm paper:
- // http://ieeexplore.ieee.org/xpl/login.jsp?tp=&arnumber=4608934&url=http%3A%2F%2Fieeexplore.ieee.org%2Fstamp%2Fstamp.jsp%3Ftp%3D%26arnumber%3D4608934
- //
- //=============================================================================================
- //-------------------------------------------------------------------------------------------
- // Header files
- #include "MahonyAHRS.h"
- #include <math.h>
- //-------------------------------------------------------------------------------------------
- // Definitions
- #define twoKpDef (120.0f * 0.5f) // 2 * proportional gain
- #define twoKiDef (0.5f * 1.0f) // 2 * integral gain
- #define sampleFrequency 100 //²ÉÑùƵÂÊ
- float q0, q1, q2, q3; // quaternion of sensor frame relative to auxiliary frame
- float integralFBx, integralFBy, integralFBz; // integral error terms scaled by Ki
- float invSampleFreq;
- float roll, pitch, yaw;
- char anglesComputed;
- void Mahony_Init(void)
- {
- q0 = 1.0f;
- q1 = 0.0f;
- q2 = 0.0f;
- q3 = 0.0f;
- integralFBx = 0.0f;
- integralFBy = 0.0f;
- integralFBz = 0.0f;
- anglesComputed = 0;
- invSampleFreq = 1.0f / sampleFrequency;
- }
- float Mahony_invSqrt(float x)
- {
- float halfx = 0.5f * x;
- float y = x;
- long i = *(long*)&y;
- i = 0x5f3759df - (i>>1);
- y = *(float*)&i;
- y = y * (1.5f - (halfx * y * y));
- y = y * (1.5f - (halfx * y * y));
- return y;
- }
- void Mahony_update(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz)
- {
- 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 valid
- // (avoids NaN in accelerometer normalisation)
- if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) {
- // Normalise accelerometer measurement
- recipNorm = Mahony_invSqrt(ax * ax + ay * ay + az * az);
- ax *= recipNorm;
- ay *= recipNorm;
- az *= recipNorm;
- // Normalise magnetometer measurement
- recipNorm = Mahony_invSqrt(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(twoKiDef > 0.0f) {
- // integral error scaled by Ki
- integralFBx += twoKiDef * halfex * invSampleFreq;
- integralFBy += twoKiDef * halfey * invSampleFreq;
- integralFBz += twoKiDef * halfez * invSampleFreq;
- 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 += twoKpDef * halfex;
- gy += twoKpDef * halfey;
- gz += twoKpDef * halfez;
- }
- // Integrate rate of change of quaternion
- gx *= (0.5f * invSampleFreq); // pre-multiply common factors
- gy *= (0.5f * invSampleFreq);
- gz *= (0.5f * invSampleFreq);
- 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 = Mahony_invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
- q0 *= recipNorm;
- q1 *= recipNorm;
- q2 *= recipNorm;
- q3 *= recipNorm;
- anglesComputed = 0;
- }
- void Mahony_computeAngles()
- {
- roll = atan2f(q0*q1 + q2*q3, 0.5f - q1*q1 - q2*q2);
- pitch = asinf(-2.0f * (q1*q3 - q0*q2));
- yaw = atan2f(q1*q2 + q0*q3, 0.5f - q2*q2 - q3*q3);
- anglesComputed = 1;
- }
- float getRoll() {
- if (!anglesComputed) Mahony_computeAngles();
- return roll * 57.29578f;
- }
- float getPitch() {
- if (!anglesComputed) Mahony_computeAngles();
- return pitch * 57.29578f;
- }
- float getYaw() {
- if (!anglesComputed) Mahony_computeAngles();
- return yaw * 57.29578f + 180.0f;
- }
- //============================================================================================
- // END OF CODE
- //============================================================================================
|