Class of MPU9250

Dependencies:   AHRS_fillter mbed

Fork of MPU9250AHRS by BE@R lab

Revision:
6:5665d427bceb
Child:
7:3e74239e3778
diff -r d31487b34216 -r 5665d427bceb AHRS.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/AHRS.cpp	Wed Jan 20 02:34:07 2016 +0000
@@ -0,0 +1,574 @@
+#include "AHRS.h"
+
+#define Kp 5.1f * 5.0f // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral
+#define Ki 1.0f
+
+/*AHRS::AHRS(PinName sda, PinName scl, PinName tx, PinName rx, int address):MPU9250(sda,scl,tx,rx,address)
+{
+    for(int i=0; i<=3; i++) {
+        eInt[i] = 0;
+        q[i] = 0;     // vector to hold quaternion
+    }
+
+    q[0] = 1.0f;
+
+    PI = 3.14159265358979323846f;
+    GyroMeasError = PI * (60.0f / 180.0f);     // gyroscope measurement error in rads/s (start at 60 deg/s), then reduce after ~10 s to 3
+    beta = sqrt(3.0f / 4.0f) * GyroMeasError;  // compute beta
+    GyroMeasDrift = PI * (1.0f / 180.0f);      // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s)
+    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
+}*/
+
+/*void AHRS::MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz, float deltat)
+{
+    float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3];   // short name local variable for readability
+    float norm;
+    float hx, hy, _2bx, _2bz;
+    float s1, s2, s3, s4;
+    float qDot1, qDot2, qDot3, qDot4;
+
+    // Auxiliary variables to avoid repeated arithmetic
+    float _2q1mx;
+    float _2q1my;
+    float _2q1mz;
+    float _2q2mx;
+    float _4bx;
+    float _4bz;
+    float _2q1 = 2.0f * q1;
+    float _2q2 = 2.0f * q2;
+    float _2q3 = 2.0f * q3;
+    float _2q4 = 2.0f * q4;
+    float _2q1q3 = 2.0f * q1 * q3;
+    float _2q3q4 = 2.0f * q3 * q4;
+    float q1q1 = q1 * q1;
+    float q1q2 = q1 * q2;
+    float q1q3 = q1 * q3;
+    float q1q4 = q1 * q4;
+    float q2q2 = q2 * q2;
+    float q2q3 = q2 * q3;
+    float q2q4 = q2 * q4;
+    float q3q3 = q3 * q3;
+    float q3q4 = q3 * q4;
+    float q4q4 = q4 * q4;
+
+    // Normalise accelerometer measurement
+    norm = sqrt(ax * ax + ay * ay + az * az);
+    if (norm == 0.0f) return; // handle NaN
+    norm = 1.0f/norm;
+    ax *= norm;
+    ay *= norm;
+    az *= norm;
+
+    // Normalise magnetometer measurement
+    norm = sqrt(mx * mx + my * my + mz * mz);
+    if (norm == 0.0f) return; // handle NaN
+    norm = 1.0f/norm;
+    mx *= norm;
+    my *= norm;
+    mz *= norm;
+
+    // Reference direction of Earth's magnetic field
+    _2q1mx = 2.0f * q1 * mx;
+    _2q1my = 2.0f * q1 * my;
+    _2q1mz = 2.0f * q1 * mz;
+    _2q2mx = 2.0f * q2 * mx;
+    hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4;
+    hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4;
+    _2bx = sqrt(hx * hx + hy * hy);
+    _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4;
+    _4bx = 2.0f * _2bx;
+    _4bz = 2.0f * _2bz;
+
+    // Gradient decent algorithm corrective step
+    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);
+    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);
+    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);
+    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);
+    norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4);    // normalise step magnitude
+    norm = 1.0f/norm;
+    s1 *= norm;
+    s2 *= norm;
+    s3 *= norm;
+    s4 *= norm;
+
+    // Compute rate of change of quaternion
+    qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1;
+    qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2;
+    qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3;
+    qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4;
+
+    // Integrate to yield quaternion
+    q1 += qDot1 * deltat;
+    q2 += qDot2 * deltat;
+    q3 += qDot3 * deltat;
+    q4 += qDot4 * deltat;
+    norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);    // normalise quaternion
+    norm = 1.0f/norm;
+    q[0] = q1 * norm;
+    q[1] = q2 * norm;
+    q[2] = q3 * norm;
+    q[3] = q4 * norm;
+
+    yaw   = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]);
+    pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
+    roll  = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]);
+
+    float Xh = mx*cos(pitch)+my*sin(roll)*sin(pitch)-mz*cos(roll)*sin(pitch);
+    float Yh = my*cos(roll)+mz*sin(roll);
+
+    float yawmag = atan2(Yh,Xh)+PI;
+    //////test.printf("Xh= %f Yh= %f ",Xh,Yh);
+    //////test.printf("Yaw[mag]= %f\n\r",yawmag*180.0f/PI);
+    //test.printf(",%f",yawmag*180.0f/PI);
+
+
+
+    pitch *= 180.0f / PI;
+    yaw   *= 180.0f / PI;
+    yaw   += 180.0f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04
+    roll  *= 180.0f / PI;
+
+}
+
+
+
+// Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and
+// measured ones.
+void AHRS::MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz, float deltat)
+{
+    q1 = q[0];
+    q2 = q[1];
+    q3 = q[2];
+    q4 = q[3];   // short name local variable for readability
+
+    // Auxiliary variables to avoid repeated arithmetic
+    q1q1 = q1 * q1;
+    q1q2 = q1 * q2;
+    q1q3 = q1 * q3;
+    q1q4 = q1 * q4;
+    q2q2 = q2 * q2;
+    q2q3 = q2 * q3;
+    q2q4 = q2 * q4;
+    q3q3 = q3 * q3;
+    q3q4 = q3 * q4;
+    q4q4 = q4 * q4;
+
+    // Normalise accelerometer measurement
+    norm = sqrt(ax * ax + ay * ay + az * az);
+    if (norm == 0.0f) return; // handle NaN
+    norm = 1.0f / norm;        // use reciprocal for division
+    ax *= norm;
+    ay *= norm;
+    az *= norm;
+
+    // Normalise magnetometer measurement
+    norm = sqrt(mx * mx + my * my + mz * mz);
+    if (norm == 0.0f) return; // handle NaN
+    norm = 1.0f / norm;        // use reciprocal for division
+    mx *= norm;
+    my *= norm;
+    mz *= norm;
+
+    // Reference direction of Earth's magnetic field
+    hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3);
+    hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2);
+    bx = sqrt((hx * hx) + (hy * hy));
+    bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3);
+
+    // Estimated direction of gravity and magnetic field
+    vx = 2.0f * (q2q4 - q1q3);
+    vy = 2.0f * (q1q2 + q3q4);
+    vz = q1q1 - q2q2 - q3q3 + q4q4;
+    wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3);
+    wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4);
+    wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3);
+
+    // Error is cross product between estimated direction and measured direction of gravity
+    ex = (ay * vz - az * vy) + (my * wz - mz * wy);
+    ey = (az * vx - ax * vz) + (mz * wx - mx * wz);
+    ez = (ax * vy - ay * vx) + (mx * wy - my * wx);
+    if (Ki > 0.0f) {
+        eInt[0] += ex;      // accumulate integral error
+        eInt[1] += ey;
+        eInt[2] += ez;
+    } else {
+        eInt[0] = 0.0f;     // prevent integral wind up
+        eInt[1] = 0.0f;
+        eInt[2] = 0.0f;
+    }
+
+    // Apply feedback terms
+    gx = gx + Kp * ex + Ki * eInt[0];
+    gy = gy + Kp * ey + Ki * eInt[1];
+    gz = gz + Kp * ez + Ki * eInt[2];
+
+    // Integrate rate of change of quaternion
+    pa = q2;
+    pb = q3;
+    pc = q4;
+    q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat);
+    q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat);
+    q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat);
+    q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat);
+
+    // Normalise quaternion
+    norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);
+    norm = 1.0f / norm;
+    q[0] = q1 * norm;
+    q[1] = q2 * norm;
+    q[2] = q3 * norm;
+    q[3] = q4 * norm;
+
+    yaw   = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]);
+    pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
+    roll  = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]);
+
+    Xh = mx*cos(pitch)+my*sin(roll)*sin(pitch)-mz*cos(roll)*sin(pitch);
+    Yh = my*cos(roll)+mz*sin(roll);
+
+    yawmag = atan2(Yh,Xh)+PI;
+    ////////////test.printf("Xh= %f Yh= %f ",Xh,Yh);
+    //////test.printf("Yaw[mag]= %f\n\r",yawmag*180.0f/PI);
+    //test.printf(",%f",yawmag*180.0f/PI);
+
+
+
+    pitch *= 180.0f / PI;
+    yaw   *= 180.0f / PI;
+    yaw   += 180.0f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04
+    roll  *= 180.0f / PI;
+}*/
+
+void AHRS::MadgwickQuaternionUpdate()
+{
+    float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3];   // short name local variable for readability
+    float norm;
+    float hx, hy, _2bx, _2bz;
+    float s1, s2, s3, s4;
+    float qDot1, qDot2, qDot3, qDot4;
+
+    // Auxiliary variables to avoid repeated arithmetic
+    float _2q1mx;
+    float _2q1my;
+    float _2q1mz;
+    float _2q2mx;
+    float _4bx;
+    float _4bz;
+    float _2q1 = 2.0f * q1;
+    float _2q2 = 2.0f * q2;
+    float _2q3 = 2.0f * q3;
+    float _2q4 = 2.0f * q4;
+    float _2q1q3 = 2.0f * q1 * q3;
+    float _2q3q4 = 2.0f * q3 * q4;
+    float q1q1 = q1 * q1;
+    float q1q2 = q1 * q2;
+    float q1q3 = q1 * q3;
+    float q1q4 = q1 * q4;
+    float q2q2 = q2 * q2;
+    float q2q3 = q2 * q3;
+    float q2q4 = q2 * q4;
+    float q3q3 = q3 * q3;
+    float q3q4 = q3 * q4;
+    float q4q4 = q4 * q4;
+
+    // Normalise accelerometer measurement
+    norm = sqrt(ax * ax + ay * ay + az * az);
+    if (norm == 0.0f) return; // handle NaN
+    norm = 1.0f/norm;
+    ax *= norm;
+    ay *= norm;
+    az *= norm;
+
+    // Normalise magnetometer measurement
+    norm = sqrt(mx * mx + my * my + mz * mz);
+    if (norm == 0.0f) return; // handle NaN
+    norm = 1.0f/norm;
+    mx *= norm;
+    my *= norm;
+    mz *= norm;
+
+    // Reference direction of Earth's magnetic field
+    _2q1mx = 2.0f * q1 * mx;
+    _2q1my = 2.0f * q1 * my;
+    _2q1mz = 2.0f * q1 * mz;
+    _2q2mx = 2.0f * q2 * mx;
+    hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4;
+    hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4;
+    _2bx = sqrt(hx * hx + hy * hy);
+    _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4;
+    _4bx = 2.0f * _2bx;
+    _4bz = 2.0f * _2bz;
+
+    // Gradient decent algorithm corrective step
+    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);
+    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);
+    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);
+    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);
+    norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4);    // normalise step magnitude
+    norm = 1.0f/norm;
+    s1 *= norm;
+    s2 *= norm;
+    s3 *= norm;
+    s4 *= norm;
+
+    // Compute rate of change of quaternion
+    qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1;
+    qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2;
+    qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3;
+    qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4;
+
+    // Integrate to yield quaternion
+    q1 += qDot1 * deltat;
+    q2 += qDot2 * deltat;
+    q3 += qDot3 * deltat;
+    q4 += qDot4 * deltat;
+    norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);    // normalise quaternion
+    norm = 1.0f/norm;
+    q[0] = q1 * norm;
+    q[1] = q2 * norm;
+    q[2] = q3 * norm;
+    q[3] = q4 * norm;
+
+    yaw   = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]);
+    pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
+    roll  = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]);
+
+    float Xh = mx*cos(pitch)+my*sin(roll)*sin(pitch)-mz*cos(roll)*sin(pitch);
+    float Yh = my*cos(roll)+mz*sin(roll);
+
+    float yawmag = atan2(Yh,Xh)+PI;
+    //////test.printf("Xh= %f Yh= %f ",Xh,Yh);
+    //////test.printf("Yaw[mag]= %f\n\r",yawmag*180.0f/PI);
+    //test.printf(",%f",yawmag*180.0f/PI);
+
+
+
+    pitch *= 180.0f / PI;
+    yaw   *= 180.0f / PI;
+    yaw   += 180.0f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04
+    roll  *= 180.0f / PI;
+
+}
+
+
+
+// Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and
+// measured ones.
+void AHRS::MahonyQuaternionUpdate()
+{
+    q1 = q[0];
+    q2 = q[1];
+    q3 = q[2];
+    q4 = q[3];   // short name local variable for readability
+
+    // Auxiliary variables to avoid repeated arithmetic
+    q1q1 = q1 * q1;
+    q1q2 = q1 * q2;
+    q1q3 = q1 * q3;
+    q1q4 = q1 * q4;
+    q2q2 = q2 * q2;
+    q2q3 = q2 * q3;
+    q2q4 = q2 * q4;
+    q3q3 = q3 * q3;
+    q3q4 = q3 * q4;
+    q4q4 = q4 * q4;
+
+    // Normalise accelerometer measurement
+    norm = sqrt(ax * ax + ay * ay + az * az);
+    if (norm == 0.0f) return; // handle NaN
+    norm = 1.0f / norm;        // use reciprocal for division
+    ax *= norm;
+    ay *= norm;
+    az *= norm;
+
+    // Normalise magnetometer measurement
+    norm = sqrt(mx * mx + my * my + mz * mz);
+    if (norm == 0.0f) return; // handle NaN
+    norm = 1.0f / norm;        // use reciprocal for division
+    mx *= norm;
+    my *= norm;
+    mz *= norm;
+
+    // Reference direction of Earth's magnetic field
+    hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3);
+    hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2);
+    bx = sqrt((hx * hx) + (hy * hy));
+    bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3);
+
+    // Estimated direction of gravity and magnetic field
+    vx = 2.0f * (q2q4 - q1q3);
+    vy = 2.0f * (q1q2 + q3q4);
+    vz = q1q1 - q2q2 - q3q3 + q4q4;
+    wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3);
+    wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4);
+    wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3);
+
+    // Error is cross product between estimated direction and measured direction of gravity
+    ex = (ay * vz - az * vy) + (my * wz - mz * wy);
+    ey = (az * vx - ax * vz) + (mz * wx - mx * wz);
+    ez = (ax * vy - ay * vx) + (mx * wy - my * wx);
+    if (Ki > 0.0f) {
+        eInt[0] += ex;      // accumulate integral error
+        eInt[1] += ey;
+        eInt[2] += ez;
+    } else {
+        eInt[0] = 0.0f;     // prevent integral wind up
+        eInt[1] = 0.0f;
+        eInt[2] = 0.0f;
+    }
+
+    // Apply feedback terms
+    gx = gx + Kp * ex + Ki * eInt[0];
+    gy = gy + Kp * ey + Ki * eInt[1];
+    gz = gz + Kp * ez + Ki * eInt[2];
+
+    // Integrate rate of change of quaternion
+    pa = q2;
+    pb = q3;
+    pc = q4;
+    q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat);
+    q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat);
+    q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat);
+    q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat);
+
+    // Normalise quaternion
+    norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);
+    norm = 1.0f / norm;
+    q[0] = q1 * norm;
+    q[1] = q2 * norm;
+    q[2] = q3 * norm;
+    q[3] = q4 * norm;
+
+    yaw   = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]);
+    pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
+    roll  = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]);
+
+    Xh = mx*cos(pitch)+my*sin(roll)*sin(pitch)-mz*cos(roll)*sin(pitch);
+    Yh = my*cos(roll)+mz*sin(roll);
+
+    yawmag = atan2(Yh,Xh)+PI;
+    ////////////test.printf("Xh= %f Yh= %f ",Xh,Yh);
+    //////test.printf("Yaw[mag]= %f\n\r",yawmag*180.0f/PI);
+    //test.printf(",%f",yawmag*180.0f/PI);
+
+
+
+    pitch *= 180.0f / PI;
+    yaw   *= 180.0f / PI;
+    yaw   += 180.0f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04
+    roll  *= 180.0f / PI;
+}
+
+void AHRS::TimeStart()
+{
+    t.start();
+}
+
+void AHRS::TimeCal()
+{
+    Now = t.read_us();
+    deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update
+    lastUpdate = Now;
+
+    sum += deltat;
+    sumCount++;
+}
+
+void AHRS::Run()
+{
+    ReadRawAccGyroMag();
+    TimeCal();
+    MadgwickQuaternionUpdate();
+
+    delt_t = t.read_ms() - count;
+    if (delt_t > 500) { // update LCD once per half-second independent of read rate
+
+        /*pc.printf("ax = %f", 1000*ax);
+        pc.printf(" ay = %f", 1000*ay);
+        pc.printf(" az = %f  mg\n\r", 1000*az);
+
+        pc.printf("gx = %f", gx);
+        pc.printf(" gy = %f", gy);
+        pc.printf(" gz = %f  deg/s\n\r", gz);
+
+        pc.printf("mx = %f", mx);
+        pc.printf(" my = %f", my);
+        pc.printf(" mz = %f  mG\n\r", mz);*/
+
+
+        //pc.printf("%f,%f,%f",mx,my,mz);
+
+        whoami = readByte(AK8963_ADDRESS, AK8963_ST2);  // Read WHO_AM_I register for MPU-9250
+        // pc.printf("I AM 0x%x\n\r", whoami); pc.printf("I SHOULD BE 0x10\n\r");
+        if(whoami == 0x14) {
+            printf("I AM 0x%x\n\r", whoami);
+            while(1);
+        }
+
+
+        readTempData();
+        temperature = ((float) temperature) / 333.87f + 21.0f; // Temperature in degrees Centigrade
+        //pc.printf(" temperature = %f  C\n\r", temperature);
+
+        // pc.printf("q0 = %f\n\r", q[0]);
+        // pc.printf("q1 = %f\n\r", q[1]);
+        // pc.printf("q2 = %f\n\r", q[2]);
+        // pc.printf("q3 = %f\n\r", q[3]);
+
+        // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation.
+        // In this coordinate system, the positive z-axis is down toward Earth.
+        // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise.
+        // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative.
+        // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll.
+        // These arise from the definition of the homogeneous rotation matrix constructed from quaternions.
+        // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be
+        // applied in the correct order which for this configuration is yaw, pitch, and then roll.
+        // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links.
+        yaw   = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]);
+        pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
+        roll  = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]);
+
+        Xh = mx*cos(pitch)+my*sin(roll)*sin(pitch)-mz*cos(roll)*sin(pitch);
+        Yh = my*cos(roll)+mz*sin(roll);
+
+        yawmag = atan2(Yh,Xh)+PI;
+        //pc.printf("Xh= %f Yh= %f ",Xh,Yh);
+        printf("Yaw[mag]= %f\n\r",yawmag*180.0f/PI);
+        printf(",%f",yawmag*180.0f/PI);
+
+
+
+        pitch *= 180.0f / PI;
+        yaw   *= 180.0f / PI;
+        yaw   += 180.0f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04
+        roll  *= 180.0f / PI;
+
+        //pc.printf(",%f,%f,%f\n",roll,pitch,yaw);
+        printf("Yaw, Pitch, Roll: %f %f %f\n\r", yaw, pitch, roll);
+        //pc.printf("average rate = %f\n\r", (float) sumCount/sum);
+//    sprintf(buffer, "YPR: %f %f %f", yaw, pitch, roll);
+//    lcd.printString(buffer, 0, 4);
+//    sprintf(buffer, "rate = %f", (float) sumCount/sum);
+//    lcd.printString(buffer, 0, 5);
+
+
+
+
+        myled= !myled;
+        count = t.read_ms();
+
+        if(count > 1<<21) {
+            t.start(); // start the timer over again if ~30 minutes has passed
+            count = 0;
+            deltat= 0;
+            lastUpdate = t.read_us();
+        }
+        sum = 0;
+        sumCount = 0;
+    }
+}
+
+void AHRS::printRollPitchYaw()
+{
+    //test.printf("roll : %f, pitch : %f, yaw : %f\n",roll,pitch,yaw);
+}
\ No newline at end of file