Two-Wheel-Self-Balancing-Ro.../selfbalance-madgwick/Madgwick.cpp

250 lines
9.2 KiB
C++
Raw Normal View History

2024-03-28 23:34:03 +01:00
//=============================================================================================
// Madgwick.c
//=============================================================================================
//
// Implementation of Madgwick's IMU and AHRS 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
// 19/02/2012 SOH Madgwick Magnetometer measurement is normalised
//
//=============================================================================================
//-------------------------------------------------------------------------------------------
// Header files
#include "Madgwick.h"
#include <math.h>
#include <stdint.h>
#include <Arduino.h>
//-------------------------------------------------------------------------------------------
// Definitions
#define sampleFreqDef 512.0f // sample frequency in Hz
//============================================================================================
// Functions
//-------------------------------------------------------------------------------------------
// AHRS algorithm update
Madgwick::Madgwick() {
q0 = 1.0f;
q1 = 0.0f;
q2 = 0.0f;
q3 = 0.0f;
now = micros();
}
void Madgwick::update(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz) {
float recipNorm;
float s0, s1, s2, s3;
float qDot1, qDot2, qDot3, qDot4;
float hx, hy;
float _2q0mx, _2q0my, _2q0mz, _2q1mx, _2bx, _2bz, _4bx, _4bz, _2q0, _2q1, _2q2, _2q3, _2q0q2, _2q2q3, q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3;
// Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation)
if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) {
updateIMU(gx, gy, gz, ax, ay, az);
return;
}
now = micros();
// Set integration time by time elapsed since last filter update
delta_t = ((now - last_update) / (float)1000000.0f);
last_update = now;
// Convert gyroscope degrees/sec to radians/sec
gx *= (float)0.0174533f;
gy *= (float)0.0174533f;
gz *= (float)0.0174533f;
// Rate of change of quaternion from gyroscope
qDot1 = (float)0.5f * (-q1 * gx - q2 * gy - q3 * gz);
qDot2 = (float)0.5f * (q0 * gx + q2 * gz - q3 * gy);
qDot3 = (float)0.5f * (q0 * gy - q1 * gz + q3 * gx);
qDot4 = (float)0.5f * (q0 * gz + q1 * gy - q2 * gx);
// Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
if(!((ax == (float)0.0f) && (ay == (float)0.0f) && (az == (float)0.0f))) {
// Normalise accelerometer measurement
recipNorm = invSqrt(ax * ax + ay * ay + az * az);
ax *= recipNorm;
ay *= recipNorm;
az *= recipNorm;
// Normalise magnetometer measurement
recipNorm = invSqrt(mx * mx + my * my + mz * mz);
mx *= recipNorm;
my *= recipNorm;
mz *= recipNorm;
// Auxiliary variables to avoid repeated arithmetic
_2q0mx = (float)2.0f * q0 * mx;
_2q0my = (float)2.0f * q0 * my;
_2q0mz = (float)2.0f * q0 * mz;
_2q1mx = (float)2.0f * q1 * mx;
_2q0 = (float)2.0f * q0;
_2q1 = (float)2.0f * q1;
_2q2 = (float)2.0f * q2;
_2q3 = (float)2.0f * q3;
_2q0q2 = (float)2.0f * q0 * q2;
_2q2q3 = (float)2.0f * q2 * q3;
q0q0 = q0 * q0;
q0q1 = q0 * q1;
q0q2 = q0 * q2;
q0q3 = q0 * q3;
q1q1 = q1 * q1;
q1q2 = q1 * q2;
q1q3 = q1 * q3;
q2q2 = q2 * q2;
q2q3 = q2 * q3;
q3q3 = q3 * q3;
// Reference direction of Earth's magnetic field
hx = mx * q0q0 - _2q0my * q3 + _2q0mz * q2 + mx * q1q1 + _2q1 * my * q2 + _2q1 * mz * q3 - mx * q2q2 - mx * q3q3;
hy = _2q0mx * q3 + my * q0q0 - _2q0mz * q1 + _2q1mx * q2 - my * q1q1 + my * q2q2 + _2q2 * mz * q3 - my * q3q3;
_2bx = sqrtf(hx * hx + hy * hy);
_2bz = -_2q0mx * q2 + _2q0my * q1 + mz * q0q0 + _2q1mx * q3 - mz * q1q1 + _2q2 * my * q3 - mz * q2q2 + mz * q3q3;
_4bx = (float)2.0f * _2bx;
_4bz = (float)2.0f * _2bz;
// Gradient decent algorithm corrective step
s0 = -_2q2 * ((float)2.0f * q1q3 - _2q0q2 - ax) + _2q1 * ((float)2.0f * q0q1 + _2q2q3 - ay) - _2bz * q2 * (_2bx * ((float)0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (-_2bx * q3 + _2bz * q1) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + _2bx * q2 * (_2bx * (q0q2 + q1q3) + _2bz * ((float)0.5f - q1q1 - q2q2) - mz);
s1 = _2q3 * ((float)2.0f * q1q3 - _2q0q2 - ax) + _2q0 * ((float)2.0f * q0q1 + _2q2q3 - ay) - (float)4.0f * q1 * (1 - (float)2.0f * q1q1 - (float)2.0f * q2q2 - az) + _2bz * q3 * (_2bx * ((float)0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (_2bx * q2 + _2bz * q0) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + (_2bx * q3 - _4bz * q1) * (_2bx * (q0q2 + q1q3) + _2bz * ((float)0.5f - q1q1 - q2q2) - mz);
s2 = -_2q0 * ((float)2.0f * q1q3 - _2q0q2 - ax) + _2q3 * ((float)2.0f * q0q1 + _2q2q3 - ay) - (float)4.0f * q2 * (1 - (float)2.0f * q1q1 - (float)2.0f * q2q2 - az) + (-_4bx * q2 - _2bz * q0) * (_2bx * ((float)0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (_2bx * q1 + _2bz * q3) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + (_2bx * q0 - _4bz * q2) * (_2bx * (q0q2 + q1q3) + _2bz * ((float)0.5f - q1q1 - q2q2) - mz);
s3 = _2q1 * ((float)2.0f * q1q3 - _2q0q2 - ax) + _2q2 * ((float)2.0f * q0q1 + _2q2q3 - ay) + (-_4bx * q3 + _2bz * q1) * (_2bx * ((float)0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (-_2bx * q0 + _2bz * q2) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + _2bx * q1 * (_2bx * (q0q2 + q1q3) + _2bz * ((float)0.5f - q1q1 - q2q2) - mz);
recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude
s0 *= recipNorm;
s1 *= recipNorm;
s2 *= recipNorm;
s3 *= recipNorm;
// Apply feedback step
qDot1 -= beta * s0;
qDot2 -= beta * s1;
qDot3 -= beta * s2;
qDot4 -= beta * s3;
}
// Integrate rate of change of quaternion to yield quaternion
q0 += qDot1 * delta_t;
q1 += qDot2 * delta_t;
q2 += qDot3 * delta_t;
q3 += qDot4 * delta_t;
// Normalise quaternion
recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
q0 *= recipNorm;
q1 *= recipNorm;
q2 *= recipNorm;
q3 *= recipNorm;
}
//-------------------------------------------------------------------------------------------
// IMU algorithm update
void Madgwick::updateIMU(float gx, float gy, float gz, float ax, float ay, float az) {
float recipNorm;
float s0, s1, s2, s3;
float qDot1, qDot2, qDot3, qDot4;
float _2q0, _2q1, _2q2, _2q3, _4q0, _4q1, _4q2 ,_8q1, _8q2, q0q0, q1q1, q2q2, q3q3;
// Convert gyroscope degrees/sec to radians/sec
gx *= (float)0.0174533f;
gy *= (float)0.0174533f;
gz *= (float)0.0174533f;
now = micros();
// Set integration time by time elapsed since last filter update
delta_t = ((now - last_update) / (float)1000000.0f);
last_update = now;
// Rate of change of quaternion from gyroscope
qDot1 = (float)0.5f * (-q1 * gx - q2 * gy - q3 * gz);
qDot2 = (float)0.5f * (q0 * gx + q2 * gz - q3 * gy);
qDot3 = (float)0.5f * (q0 * gy - q1 * gz + q3 * gx);
qDot4 = (float)0.5f * (q0 * gz + q1 * gy - q2 * gx);
// Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) {
// Normalise accelerometer measurement
recipNorm = invSqrt(ax * ax + ay * ay + az * az);
ax *= recipNorm;
ay *= recipNorm;
az *= recipNorm;
// Auxiliary variables to avoid repeated arithmetic
_2q0 = (float)2.0f * q0;
_2q1 = (float)2.0f * q1;
_2q2 = (float)2.0f * q2;
_2q3 = (float)2.0f * q3;
_4q0 = (float)4.0f * q0;
_4q1 = (float)4.0f * q1;
_4q2 = (float)4.0f * q2;
_8q1 = (float)8.0f * q1;
_8q2 = (float)8.0f * q2;
q0q0 = q0 * q0;
q1q1 = q1 * q1;
q2q2 = q2 * q2;
q3q3 = q3 * q3;
// Gradient decent algorithm corrective step
s0 = _4q0 * q2q2 + _2q2 * ax + _4q0 * q1q1 - _2q1 * ay;
s1 = _4q1 * q3q3 - _2q3 * ax + 4.0f * q0q0 * q1 - _2q0 * ay - _4q1 + _8q1 * q1q1 + _8q1 * q2q2 + _4q1 * az;
s2 = (float)4.0f * q0q0 * q2 + _2q0 * ax + _4q2 * q3q3 - _2q3 * ay - _4q2 + _8q2 * q1q1 + _8q2 * q2q2 + _4q2 * az;
s3 = (float)4.0f * q1q1 * q3 - _2q1 * ax + 4.0f * q2q2 * q3 - _2q2 * ay;
recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude
s0 *= recipNorm;
s1 *= recipNorm;
s2 *= recipNorm;
s3 *= recipNorm;
// Apply feedback step
qDot1 -= beta * s0;
qDot2 -= beta * s1;
qDot3 -= beta * s2;
qDot4 -= beta * s3;
}
// Integrate rate of change of quaternion to yield quaternion
q0 += qDot1 * delta_t;
q1 += qDot2 * delta_t;
q2 += qDot3 * delta_t;
q3 += qDot4 * delta_t;
// Normalise quaternion
recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
q0 *= recipNorm;
q1 *= recipNorm;
q2 *= recipNorm;
q3 *= recipNorm;
}
//-------------------------------------------------------------------------------------------
// Fast inverse square-root
// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root
float Madgwick::invSqrt(float x) {
float halfx = 0.5f * x;
float y = x;
long i = *(long*)&y;
i = 0x5f3759df - (i>>1);
y = *(float*)&i;
y = y * (1.5f - (halfx * y * y));
y = y * (1.5f - (halfx * y * y));
return y;
}
//-------------------------------------------------------------------------------------------