Use hexiwear as a GPSIMU-AHRS for Nikon DSLR cameras
Dependencies: FXOS8700CQ FXAS21000 MBed_Adafruit-GPS-Library Hexi_OLED_SSD1351 Hexi_KW40Z Madgwick
Fork of Hexi_Blinky_Example by
Revision 24:cbdf0f7d33bd, committed 2016-09-20
- Comitter:
- whatnick
- Date:
- Tue Sep 20 04:18:34 2016 +0000
- Parent:
- 23:f170a1d72a84
- Child:
- 25:6e43bbe76aec
- Commit message:
- Added sensor fusion code
Changed in this revision
| main.cpp | Show annotated file Show diff for this revision Revisions of this file |
| sensor_fusion.h | Show annotated file Show diff for this revision Revisions of this file |
--- a/main.cpp Mon Sep 19 16:27:18 2016 +0000
+++ b/main.cpp Tue Sep 20 04:18:34 2016 +0000
@@ -3,9 +3,12 @@
#include "FXAS21000.h"
#include "MBed_Adafruit_GPS.h"
#include "Hexi_OLED_SSD1351.h"
+#include "sensor_fusion.h"
#include "images.h"
+
#include "rtos.h"
+
DigitalOut myled(LED1);
Serial gps(PTD3,PTD2);
@@ -47,18 +50,16 @@
float gyro_data[3];
Timer t;
-int lastUpdate;
void gps_thread(void const *args)
{
while (true) {
c = myGPS.read(); //queries the GPS
- if (c) {
- LOG("%c", c); //this line will echo the GPS data if not paused
- }
+
//check if we recieved a new message from GPS, if so, attempt to parse it,
if ( myGPS.newNMEAreceived() ) {
if ( !myGPS.parse(myGPS.lastNMEA()) ) {
+ LOG(myGPS.lastNMEA());
continue;
}
}
@@ -72,37 +73,37 @@
acc.getAxis(acc_data);
mag.getAxis(mag_data);
gyro.ReadXYZ(gyro_data);
- /*
+
LOG("FXOS8700Q ACC: X=%1.4f Y=%1.4f Z=%1.4f ", acc_data.x, acc_data.y, acc_data.z);
LOG(" MAG: X=%4.1f Y=%4.1f Z=%4.1f\r\n", mag_data.x, mag_data.y, mag_data.z);
LOG("FXAS21000 X=%4.2f Y=%4.2f Z=%4.1f\r\n", gyro_data[0], gyro_data[1], gyro_data[2]);
- */
+
acc.getX(&faX);
acc.getY(&faY);
acc.getZ(&faZ);
mag.getX(&fmX);
mag.getY(&fmY);
mag.getZ(&fmZ);
- /*
+
LOG("FXOS8700Q ACC: X=%1.4f Y=%1.4f Z=%1.4f ", faX, faY, faZ);
LOG(" MAG: X=%4.1f Y=%4.1f Z=%4.1f\r\n", fmX, fmY, fmZ);
- */
+
acc.getAxis(acc_raw);
mag.getAxis(mag_raw);
- /*
+
LOG("FXOS8700Q ACC: X=%d Y=%d Z=%d ", acc_raw.x, acc_raw.y, acc_raw.z);
LOG(" MAG: X=%d Y=%d Z=%d\r\n", mag_raw.x, mag_raw.y, mag_raw.z);
- */
+
acc.getX(&raX);
acc.getY(&raY);
acc.getZ(&raZ);
mag.getX(&rmX);
mag.getY(&rmY);
mag.getZ(&rmZ);
- /*
+
LOG("FXOS8700Q ACC: X=%d Y=%d Z=%d ", raX, raY, raZ);
LOG(" MAG: X=%d Y=%d Z=%d\r\n\n", rmX, rmY, rmZ);
- */
+
Thread::wait(100);
}
}
@@ -131,9 +132,6 @@
pc.baud(115200);
#endif
- Thread gps_t(gps_thread);
- Thread imu_t(imu_thread);
-
acc.enable();
LOG("\r\n\nFXOS8700Q Who Am I= %X\r\n", acc.whoAmI());
LOG("\r\n\nFXAS21000 Who Am I= %X\r\n", gyro.getWhoAmI());
@@ -192,6 +190,9 @@
textProperties.alignParam = OLED_TEXT_ALIGN_RIGHT;
oled.SetTextProperties(&textProperties);
+ //Start read and update threads
+ Thread gps_t(gps_thread);
+ Thread imu_t(imu_thread);
while (true) {
/* Format the MAG reading */
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_fusion.h Tue Sep 20 04:18:34 2016 +0000
@@ -0,0 +1,211 @@
+#ifndef SENSOR_FUSION_H
+#define SENSOR_FUSION_H
+
+#include "mbed.h"
+
+// parameters for 6 DoF sensor fusion calculations
+float PI = 3.14159265358979323846f;
+float GyroMeasError = PI * (60.0f / 180.0f); // gyroscope measurement error in rads/s (start at 60 deg/s), then reduce after ~10 s to 3
+float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta
+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
+#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
+
+
+float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion
+float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method
+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
+
+// 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)
+// which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute
+// device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc.
+// 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 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;
+
+}
+
+// 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 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;
+
+ // 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;
+
+}
+
+#endif
\ No newline at end of file
