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 Hexiwear

/media/uploads/whatnick/hexiwear_docking_station_numbers.jpg

Files at this revision

API Documentation at this revision

Comitter:
whatnick
Date:
Thu Feb 02 03:08:13 2017 +0000
Parent:
25:6e43bbe76aec
Child:
27:8c84611a4ca5
Commit message:
Changed acc-mag library

Changed in this revision

FXOS8700CQ.lib Show annotated file Show diff for this revision Revisions of this file
FXOS8700Q.lib Show diff for this revision Revisions of this file
Hexi_KW40Z.lib Show annotated file Show diff for this revision Revisions of this file
Hexi_OLED_SSD1351.lib Show annotated file Show diff for this revision Revisions of this file
Madgwick.lib Show annotated file Show diff for this revision Revisions of this file
main.cpp Show annotated file Show diff for this revision Revisions of this file
sensor_fusion.h Show diff for this revision Revisions of this file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/FXOS8700CQ.lib	Thu Feb 02 03:08:13 2017 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/eencae/code/FXOS8700CQ/#b320fe026cc5
--- a/FXOS8700Q.lib	Sat Sep 24 06:10:54 2016 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,1 +0,0 @@
-http://mbed.org/users/JimCarver/code/FXOS8700Q/#5553a64d0762
--- a/Hexi_KW40Z.lib	Sat Sep 24 06:10:54 2016 +0000
+++ b/Hexi_KW40Z.lib	Thu Feb 02 03:08:13 2017 +0000
@@ -1,1 +1,1 @@
-https://developer.mbed.org/teams/Hexiwear/code/Hexi_KW40Z/#8c7c1cc024ed
+https://developer.mbed.org/teams/Hexiwear/code/Hexi_KW40Z/#3f5ed7abc5c7
--- a/Hexi_OLED_SSD1351.lib	Sat Sep 24 06:10:54 2016 +0000
+++ b/Hexi_OLED_SSD1351.lib	Thu Feb 02 03:08:13 2017 +0000
@@ -1,1 +1,1 @@
-https://developer.mbed.org/teams/Hexiwear/code/Hexi_OLED_SSD1351/#9961c525e249
+https://developer.mbed.org/teams/Hexiwear/code/Hexi_OLED_SSD1351/#ae5fad429790
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Madgwick.lib	Thu Feb 02 03:08:13 2017 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/Anaesthetix/code/Madgwick/#9b434b5e28d4
--- a/main.cpp	Sat Sep 24 06:10:54 2016 +0000
+++ b/main.cpp	Thu Feb 02 03:08:13 2017 +0000
@@ -1,9 +1,9 @@
 #include "mbed.h"
-#include "FXOS8700Q.h"
+#include "FXOS8700CQ.h"
 #include "FXAS21000.h"
 #include "MBed_Adafruit_GPS.h"
 #include "Hexi_OLED_SSD1351.h"
-#include "sensor_fusion.h"
+#include "MadgwickAHRS.h"
 #include "images.h"
 
 #include "rtos.h"
@@ -35,20 +35,11 @@
 #define RED 0xFF0000
 #define BLUE 0x0000FF
 
-FXOS8700Q_acc acc( PTC11, PTC10, FXOS8700CQ_SLAVE_ADDR0); // Proper Ports and I2C Address for Hexiwear
-FXOS8700Q_mag mag( PTC11, PTC10, FXOS8700CQ_SLAVE_ADDR0); // Proper Ports and I2C Address for Hexiwear
-MotionSensorDataUnits mag_data;
-MotionSensorDataUnits acc_data;
-
-MotionSensorDataCounts mag_raw;
-MotionSensorDataCounts acc_raw;
+FXOS8700CQ combo( PTC11, PTC10); // Proper Ports and I2C Address for Hexiwear
 
 FXAS21000 gyro( PTC11, PTC10); // Proper Ports for Hexiwear
 
-float faX, faY, faZ;
-float fmX, fmY, fmZ;
-int16_t raX, raY, raZ;
-int16_t rmX, rmY, rmZ;
+Data combo_data;
 float gyro_data[3];
 
 Timer t;
@@ -78,45 +69,8 @@
 void imu_thread(void)
 {
     while(true) {
-        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);
-        
-        MadgwickQuaternionUpdate(faX,faY,faZ,gyro_data[0],gyro_data[1],gyro_data[2],fmX,fmY,fmZ);
-        calcEuler();
-        
-        LOG("EULER: Y=%f R=%f P=%f\n", yaw,roll,pitch);
-        
+        combo_data = combo.get_values();
         Thread::wait(10);
     }
 }
@@ -148,9 +102,10 @@
 //Connect to Nikon D800 UART at 4800baud
     camera.baud(4800);
 
-    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());
+//Initialise gyro
+    char whoami = gyro.getWhoAmI();
+//Initialise combo (acc&mag)
+    combo.init();
 
     /* Get OLED Class Default Text Properties */
     oled_text_properties_t textProperties = {0};
@@ -211,16 +166,6 @@
     imu_t.start(imu_thread);
 
     while (true) {     
-        /* Format the MAG reading */
-        sprintf(text,"%.1f %.1f %.1f",fmX,fmY,fmZ);
-        /* Display Mag readings to 1 decimal */
-        oled.TextBox((uint8_t *)text,15,15,80,15); /*Expand textbox for more digits*/
-
-        /* Format the ACC reading */
-        sprintf(text,"%.2f %.2f %.2f",faX,faY,faZ);
-        /* Display acceleration to 2 decimal */
-        oled.TextBox((uint8_t *)text,15,30,80,15); /*Expand textbox for more digits*/
-
         /* Format the GYRO reading */
         sprintf(text,"%.2f %.2f %.2f",gyro_data[0],gyro_data[1],gyro_data[2]);
         /* Display gyro to 2 decimal */
--- a/sensor_fusion.h	Sat Sep 24 06:10:54 2016 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,223 +0,0 @@
-#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 mag_dec = 7.97;                            // Adelaide Magnetic declination http://www.magnetic-declination.com/Australia/Adelaide/116230.html
-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;
-
-}
-
-void calcEuler()
-{
-    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   -= mag_dec; // Declination from BLE/SD storage at GPS location
-    roll  *= 180.0f / PI;
-}
-
-#endif
\ No newline at end of file