Skip to content

Commit

Permalink
Convert to Arduino library format
Browse files Browse the repository at this point in the history
  • Loading branch information
PaulStoffregen committed Mar 15, 2016
1 parent 5151b06 commit 4391754
Show file tree
Hide file tree
Showing 4 changed files with 88 additions and 32 deletions.
21 changes: 21 additions & 0 deletions keywords.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
#######################################
# Datatypes (KEYWORD1)
#######################################

Mahony KEYWORD1

#######################################
# Methods and Functions (KEYWORD2)
#######################################

update KEYWORD2
updateIMU KEYWORD2
getPitch KEYWORD2
getYaw KEYWORD2
getRoll KEYWORD2


#######################################
# Constants (LITERAL1)
#######################################

9 changes: 9 additions & 0 deletions library.properties
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
name=Mahony
version=1.0
author=Arduino
maintainer=None
sentence=Helpers for MahonyAHRS algorithm
paragraph=This library wraps the implementation of MahonyAHRS algorithm to get orientation of an object based on accelerometer and gyroscope readings
category=Data Processing
url=https://github.com/PaulStoffregen/Mahony
architectures=*
67 changes: 41 additions & 26 deletions src/MahonyAHRS.c → src/MahonyAHRS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,19 @@
//=====================================================================================================
//
// Madgwick's implementation of Mayhony's AHRS algorithm.
// See: http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms
// 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
//
//=====================================================================================================

//---------------------------------------------------------------------------------------------------
Expand All @@ -20,7 +27,7 @@
//---------------------------------------------------------------------------------------------------
// Definitions

#define sampleFreq 512.0f // sample frequency in Hz
#define sampleFreq 512.0f // sample frequency in Hz
#define twoKpDef (2.0f * 0.5f) // 2 * proportional gain
#define twoKiDef (2.0f * 0.0f) // 2 * integral gain

Expand All @@ -32,28 +39,36 @@ volatile float twoKi = twoKiDef; // 2 * integral gain (Ki)
volatile float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to auxiliary frame
volatile float integralFBx = 0.0f, integralFBy = 0.0f, integralFBz = 0.0f; // integral error terms scaled by Ki

//---------------------------------------------------------------------------------------------------
// Function declarations

float invSqrt(float x);

//====================================================================================================
// Functions

//---------------------------------------------------------------------------------------------------
// AHRS algorithm update

void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz) {
Mahony::Mahony() {
twoKp = twoKpDef; // 2 * proportional gain (Kp)
twoKi = twoKiDef; // 2 * integral gain (Ki)
q0 = 1.0f;
q1 = 0.0f;
q2 = 0.0f;
q3 = 0.0f;
integralFBx = 0.0f;
integralFBy = 0.0f;
integralFBz = 0.0f;
}

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 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;

// Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation)
if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) {
MahonyAHRSupdateIMU(gx, gy, gz, ax, ay, az);
updateIMU(gx, gy, gz, ax, ay, az);
return;
}

Expand All @@ -64,13 +79,13 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az
recipNorm = invSqrt(ax * ax + ay * ay + az * az);
ax *= recipNorm;
ay *= recipNorm;
az *= recipNorm;
az *= recipNorm;

// Normalise magnetometer measurement
recipNorm = invSqrt(mx * mx + my * my + mz * mz);
mx *= recipNorm;
my *= recipNorm;
mz *= recipNorm;
mz *= recipNorm;

// Auxiliary variables to avoid repeated arithmetic
q0q0 = q0 * q0;
Expand All @@ -82,7 +97,7 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az
q1q3 = q1 * q3;
q2q2 = q2 * q2;
q2q3 = q2 * q3;
q3q3 = q3 * 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));
Expand All @@ -94,10 +109,10 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az
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);
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);
Expand All @@ -123,7 +138,7 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az
gy += twoKp * halfey;
gz += twoKp * halfez;
}

// Integrate rate of change of quaternion
gx *= (0.5f * (1.0f / sampleFreq)); // pre-multiply common factors
gy *= (0.5f * (1.0f / sampleFreq));
Expand All @@ -134,8 +149,8 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az
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);
q3 += (qa * gz + qb * gy - qc * gx);

// Normalise quaternion
recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
q0 *= recipNorm;
Expand All @@ -147,7 +162,7 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az
//---------------------------------------------------------------------------------------------------
// IMU algorithm update

void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az) {
void Mahony::updateIMU(float gx, float gy, float gz, float ax, float ay, float az) {
float recipNorm;
float halfvx, halfvy, halfvz;
float halfex, halfey, halfez;
Expand All @@ -160,13 +175,13 @@ void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float
recipNorm = invSqrt(ax * ax + ay * ay + az * az);
ax *= recipNorm;
ay *= recipNorm;
az *= recipNorm;
az *= recipNorm;

// Estimated direction of gravity and vector perpendicular to magnetic flux
halfvx = q1 * q3 - q0 * q2;
halfvy = q0 * q1 + q2 * q3;
halfvz = q0 * q0 - 0.5f + q3 * q3;

// Error is sum of cross product between estimated and measured direction of gravity
halfex = (ay * halfvz - az * halfvy);
halfey = (az * halfvx - ax * halfvz);
Expand All @@ -192,7 +207,7 @@ void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float
gy += twoKp * halfey;
gz += twoKp * halfez;
}

// Integrate rate of change of quaternion
gx *= (0.5f * (1.0f / sampleFreq)); // pre-multiply common factors
gy *= (0.5f * (1.0f / sampleFreq));
Expand All @@ -203,8 +218,8 @@ void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float
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);
q3 += (qa * gz + qb * gy - qc * gx);

// Normalise quaternion
recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
q0 *= recipNorm;
Expand All @@ -217,7 +232,7 @@ void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float
// Fast inverse square-root
// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root

float invSqrt(float x) {
float Mahony::invSqrt(float x) {
float halfx = 0.5f * x;
float y = x;
long i = *(long*)&y;
Expand Down
23 changes: 17 additions & 6 deletions src/MahonyAHRS.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
//=====================================================================================================
//
// Madgwick's implementation of Mayhony's AHRS algorithm.
// See: http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms
// See: http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/
//
// Date Author Notes
// 29/09/2011 SOH Madgwick Initial release
Expand All @@ -12,19 +12,30 @@
//=====================================================================================================
#ifndef MahonyAHRS_h
#define MahonyAHRS_h
#include <math.h>

//----------------------------------------------------------------------------------------------------
// Variable declaration

extern volatile float twoKp; // 2 * proportional gain (Kp)
extern volatile float twoKi; // 2 * integral gain (Ki)
extern volatile float q0, q1, q2, q3; // quaternion of sensor frame relative to auxiliary frame
class Mahony {
private:
float twoKp; // 2 * proportional gain (Kp)
float twoKi; // 2 * integral gain (Ki)
float q0, q1, q2, q3; // quaternion of sensor frame relative to auxiliary frame
float integralFBx, integralFBy, integralFBz; // integral error terms scaled by Ki
static float invSqrt(float x);

//---------------------------------------------------------------------------------------------------
// Function declarations

void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz);
void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az);
public:
Mahony();
void update(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz);
void updateIMU(float gx, float gy, float gz, float ax, float ay, float az);
float getPitch(){return atan2f(2 * q2 * q3 - 2 * q0 * q1, 2 * q0 * q0 + 2 * q3 * q3 - 1);};
float getRoll(){return -1 * asinf(2 * q1 * q3 + 2 * q0 * q2);};
float getYaw(){return atan2f(2 * q1 * q2 - 2 * q0 * q3, 2 * q0 * q0 + 2 * q1 * q1 - 1);};
};

#endif
//=====================================================================================================
Expand Down

0 comments on commit 4391754

Please sign in to comment.