Library version of MPU9250AHRS code.
Fork of MPU9250AHRS by
Revision 5:ea541d293095, committed 2014-09-08
- Comitter:
- janekm
- Date:
- Mon Sep 08 21:50:33 2014 +0000
- Parent:
- 4:404c35f32ce3
- Commit message:
- N/A
Changed in this revision
diff -r 404c35f32ce3 -r ea541d293095 AHRS.c --- a/AHRS.c Thu Sep 04 21:19:05 2014 +0000 +++ b/AHRS.c Mon Sep 08 21:50:33 2014 +0000 @@ -1,7 +1,7 @@ #include "AHRS.h" #include "math.h" -static float eInt[3] = {0.0f, 0.0f, 0.0f}; +static float eInt[3] = {0.0f, 0.0f, 0.0f}; // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" // (see http://www.x-io.co.uk/category/open-source/ for examples and more details) @@ -10,94 +10,95 @@ // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz! - void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz, float deltat, float *q, float beta) { - 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; +void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz, float deltat, float *q, float beta) +{ + 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; + // 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 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; + // 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; + // 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; + // 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; + // 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; + // 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; } @@ -105,90 +106,90 @@ // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and // measured ones. - void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz, float deltat, float *q) { - float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability - float norm; - float hx, hy, bx, bz; - float vx, vy, vz, wx, wy, wz; - float ex, ey, ez; - float pa, pb, pc; +void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz, float deltat, float *q) +{ + float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability + float norm; + float hx, hy, bx, bz; + float vx, vy, vz, wx, wy, wz; + float ex, ey, ez; + float pa, pb, pc; - // Auxiliary variables to avoid repeated arithmetic - 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; + // Auxiliary variables to avoid repeated arithmetic + 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; // use reciprocal for division - ax *= norm; - ay *= norm; - az *= norm; + // 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; + // 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); + // 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); + // 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; - } + // 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]; + // 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); + // 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; - - } \ No newline at end of file + // 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; +} \ No newline at end of file
diff -r 404c35f32ce3 -r ea541d293095 AHRS.h --- a/AHRS.h Thu Sep 04 21:19:05 2014 +0000 +++ b/AHRS.h Mon Sep 08 21:50:33 2014 +0000 @@ -1,10 +1,18 @@ #ifndef __AHRS_H_ #define __AHRS_H_ +#ifdef __cplusplus +extern "C" { +#endif // #ifdef __cplusplus + #define Kp 2.0f * 5.0f // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral #define Ki 0.0f void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz, float deltat, float *q, float beta); void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz, float deltat, float *q); +#ifdef __cplusplus +} +#endif // #ifdef __cplusplus + #endif // __AHRS_H_ \ No newline at end of file
diff -r 404c35f32ce3 -r ea541d293095 MPU9250.h --- a/MPU9250.h Thu Sep 04 21:19:05 2014 +0000 +++ b/MPU9250.h Mon Sep 08 21:50:33 2014 +0000 @@ -217,8 +217,6 @@ float GyroMeasDrift = PI * (1.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) float 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 -float pitch, yaw, roll; -float deltat = 0.0f; // integration interval for both filter schemes int lastUpdate = 0, firstUpdate = 0, Now = 0; // used to calculate integration interval // used to calculate integration interval float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method @@ -616,7 +614,7 @@ // Configure the accelerometer for self-test writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s - wait(25); // Delay a while to let the device stabilize + wait(2); // Delay a while to let the device stabilize for( int ii = 0; ii < 200; ii++) { // get average self-test values of gyro and acclerometer @@ -639,7 +637,7 @@ // Configure the gyro and accelerometer for normal operation writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); - wait(25); // Delay a while to let the device stabilize + wait(2); // Delay a while to let the device stabilize // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg selfTest[0] = readByte(MPU9250_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results
diff -r 404c35f32ce3 -r ea541d293095 main.cpp --- a/main.cpp Thu Sep 04 21:19:05 2014 +0000 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,239 +0,0 @@ -/* MPU9250 Basic Example Code - by: Kris Winer - date: April 1, 2014 - license: Beerware - Use this code however you'd like. If you - find it useful you can buy me a beer some time. - - Demonstrate basic MPU-9250 functionality including parameterizing the register addresses, initializing the sensor, - getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to - allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and - Mahony filter algorithms. Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1. - - SDA and SCL should have external pull-up resistors (to 3.3V). - 10k resistors are on the EMSENSR-9250 breakout board. - - Hardware setup: - MPU9250 Breakout --------- Arduino - VDD ---------------------- 3.3V - VDDI --------------------- 3.3V - SDA ----------------------- A4 - SCL ----------------------- A5 - GND ---------------------- GND - - Note: The MPU9250 is an I2C sensor and uses the Arduino Wire library. - Because the sensor is not 5V tolerant, we are using a 3.3 V 8 MHz Pro Mini or a 3.3 V Teensy 3.1. - We have disabled the internal pull-ups used by the Wire library in the Wire.h/twi.c utility file. - We are also using the 400 kHz fast I2C mode by setting the TWI_FREQ to 400000L /twi.h utility file. - */ - -//#include "ST_F401_84MHZ.h" -//F401_init84 myinit(0); -#include "mbed.h" -#include "MPU9250.h" -#include "AHRS.h" - -// Using NOKIA 5110 monochrome 84 x 48 pixel display -// pin 9 - Serial clock out (SCLK) -// pin 8 - Serial data out (DIN) -// pin 7 - Data/Command select (D/C) -// pin 5 - LCD chip select (CS) -// pin 6 - LCD reset (RST) -//Adafruit_PCD8544 display = Adafruit_PCD8544(9, 8, 7, 5, 6); - -float sum = 0; -float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion - -uint32_t sumCount = 0; -char buffer[14]; -I2C i2c(p7, p6); - MPU9250 mpu9250(&i2c); - - Timer t; - - Serial pc(USBTX, USBRX); // tx, rx - - - -int main() -{ - pc.baud(9600); - - //Set up I2C - i2c.frequency(400000); // use fast (400 kHz) I2C - - pc.printf("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock); - - t.start(); - - - // Read the WHO_AM_I register, this is a good test of communication - uint8_t whoami = mpu9250.readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250); // Read WHO_AM_I register for MPU-9250 - pc.printf("I AM 0x%x\n\r", whoami); pc.printf("I SHOULD BE 0x71\n\r"); - - if (whoami == 0x71) // WHO_AM_I should always be 0x68 - { - pc.printf("MPU9250 WHO_AM_I is 0x%x\n\r", whoami); - pc.printf("MPU9250 is online...\n\r"); - sprintf(buffer, "0x%x", whoami); - wait(1); - - mpu9250.resetMPU9250(); // Reset registers to default in preparation for device calibration - mpu9250.MPU9250SelfTest(SelfTest); // Start by performing self test and reporting values - pc.printf("x-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[0]); - pc.printf("y-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[1]); - pc.printf("z-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[2]); - pc.printf("x-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[3]); - pc.printf("y-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[4]); - pc.printf("z-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[5]); - mpu9250.calibrateMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers - pc.printf("x gyro bias = %f\n\r", gyroBias[0]); - pc.printf("y gyro bias = %f\n\r", gyroBias[1]); - pc.printf("z gyro bias = %f\n\r", gyroBias[2]); - pc.printf("x accel bias = %f\n\r", accelBias[0]); - pc.printf("y accel bias = %f\n\r", accelBias[1]); - pc.printf("z accel bias = %f\n\r", accelBias[2]); - wait(2); - mpu9250.initMPU9250(); - pc.printf("MPU9250 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature - mpu9250.initAK8963(magCalibration); - pc.printf("AK8963 initialized for active data mode....\n\r"); // Initialize device for active mode read of magnetometer - pc.printf("Accelerometer full-scale range = %f g\n\r", 2.0f*(float)(1<<Ascale)); - pc.printf("Gyroscope full-scale range = %f deg/s\n\r", 250.0f*(float)(1<<Gscale)); - if(Mscale == 0) pc.printf("Magnetometer resolution = 14 bits\n\r"); - if(Mscale == 1) pc.printf("Magnetometer resolution = 16 bits\n\r"); - if(Mmode == 2) pc.printf("Magnetometer ODR = 8 Hz\n\r"); - if(Mmode == 6) pc.printf("Magnetometer ODR = 100 Hz\n\r"); - wait(1); - } - else - { - pc.printf("Could not connect to MPU9250: \n\r"); - pc.printf("%#x \n", whoami); - - while(1) ; // Loop forever if communication doesn't happen - } - - mpu9250.getAres(); // Get accelerometer sensitivity - mpu9250.getGres(); // Get gyro sensitivity - mpu9250.getMres(); // Get magnetometer sensitivity - pc.printf("Accelerometer sensitivity is %f LSB/g \n\r", 1.0f/aRes); - pc.printf("Gyroscope sensitivity is %f LSB/deg/s \n\r", 1.0f/gRes); - pc.printf("Magnetometer sensitivity is %f LSB/G \n\r", 1.0f/mRes); - magbias[0] = +470.; // User environmental x-axis correction in milliGauss, should be automatically calculated - magbias[1] = +120.; // User environmental x-axis correction in milliGauss - magbias[2] = +125.; // User environmental x-axis correction in milliGauss - - while(1) { - - // If intPin goes high, all data registers have new data - if(mpu9250.readByte(MPU9250_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt - - mpu9250.readAccelData(accelCount); // Read the x/y/z adc values - // Now we'll calculate the accleration value into actual g's - ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set - ay = (float)accelCount[1]*aRes - accelBias[1]; - az = (float)accelCount[2]*aRes - accelBias[2]; - - mpu9250.readGyroData(gyroCount); // Read the x/y/z adc values - // Calculate the gyro value into actual degrees per second - gx = (float)gyroCount[0]*gRes - gyroBias[0]; // get actual gyro value, this depends on scale being set - gy = (float)gyroCount[1]*gRes - gyroBias[1]; - gz = (float)gyroCount[2]*gRes - gyroBias[2]; - - mpu9250.readMagData(magCount); // Read the x/y/z adc values - // Calculate the magnetometer values in milliGauss - // Include factory calibration per data sheet and user environmental corrections - mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0]; // get actual magnetometer value, this depends on scale being set - my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1]; - mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2]; - } - - 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++; - -// if(lastUpdate - firstUpdate > 10000000.0f) { -// beta = 0.04; // decrease filter gain after stabilized -// zeta = 0.015; // increasey bias drift gain after stabilized - // } - - // Pass gyro rate as rad/s -// mpu9250.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); - MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz, deltat, q); - - // Serial print and/or display at 0.5 s rate independent of data rates - 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("gx = %f", mx); - pc.printf(" gy = %f", my); - pc.printf(" gz = %f mG\n\r", mz); - - tempCount = mpu9250.readTempData(); // Read the adc values - temperature = ((float) tempCount) / 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]); - -/* lcd.clear(); - lcd.printString("MPU9250", 0, 0); - lcd.printString("x y z", 0, 1); - sprintf(buffer, "%d %d %d mg", (int)(1000.0f*ax), (int)(1000.0f*ay), (int)(1000.0f*az)); - lcd.printString(buffer, 0, 2); - sprintf(buffer, "%d %d %d deg/s", (int)gx, (int)gy, (int)gz); - lcd.printString(buffer, 0, 3); - sprintf(buffer, "%d %d %d mG", (int)mx, (int)my, (int)mz); - lcd.printString(buffer, 0, 4); - */ - // 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]); - pitch *= 180.0f / PI; - yaw *= 180.0f / PI; - yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - roll *= 180.0f / PI; - - pc.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); - - 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; -} -} - - } \ No newline at end of file