From f3881efb00e800c27a9b0c9cfe382e7e1fa805a7 Mon Sep 17 00:00:00 2001 From: Olivier Matz Date: Thu, 18 Sep 2014 19:44:53 +0200 Subject: [PATCH] imu: dos2unix --- imuboard/MadgwickAHRS.c | 504 ++++++++++++++++++++-------------------- imuboard/MadgwickAHRS.h | 92 ++++---- 2 files changed, 298 insertions(+), 298 deletions(-) diff --git a/imuboard/MadgwickAHRS.c b/imuboard/MadgwickAHRS.c index 7043a7a..c6dfaee 100644 --- a/imuboard/MadgwickAHRS.c +++ b/imuboard/MadgwickAHRS.c @@ -1,252 +1,252 @@ -/* - * Copyright (c) 2014, Olivier MATZ - * Copyright (c) 2011-2012, SOH Madgwick - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ - -//============================================================================ -// MadgwickAHRS.c -//============================================================================ -// -// Implementation of Madgwick's IMU and AHRS algorithms. -// See: http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms -// -// 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 -// -//============================================================================ - -#include "MadgwickAHRS.h" -#include - -//#define sampleFreq 512.0f // sample frequency in Hz -//#define sampleFreq 46.0f // sample frequency in Hz -#define sampleFreq 85.0f // sample frequency in Hz -#define betaDef 0.1f // 2 * proportional gain - -static float invSqrt(float x) -{ - return 1.0f / sqrtf(x); -} - -/* AHRS algorithm update */ -void MadgwickAHRSupdate(const struct imu_info *imu, struct quaternion *quat) -{ - float recipNorm; - float s0, s1, s2, s3; - float qDot1, qDot2, qDot3, qDot4; - float hx, hy; - float _2q0mx, _2q0my, _2q0mz, _2q1mx, _2bx, _2bz, _4bx, _4bz; - float _2q0, _2q1, _2q2, _2q3, _2q0q2, _2q2q3, q0q0, q0q1, q0q2, q0q3; - float q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; - float mx, my, mz, ax, ay, az, gx, gy, gz; - float q0, q1, q2, q3; - - /* Use IMU algorithm if magnetometer measurement invalid (avoids NaN in - * magnetometer normalisation) */ - if ((imu->mx == 0.0f) && (imu->my == 0.0f) && (imu->mz == 0.0f)) { - MadgwickAHRSupdateIMU(imu, quat); - return; - } - - /* use local variables, it's more readable */ - q0 = quat->q0; q1 = quat->q1; q2 = quat->q2; q3 = quat->q3; - gx = imu->gx; gy = imu->gy; gz = imu->gz; - ax = imu->ax; ay = imu->ay; az = imu->az; - mx = imu->mx; my = imu->my; mz = imu->mz; - - /* Rate of change of quaternion from gyroscope */ - qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); - qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); - qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); - qDot4 = 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; - - /* Normalise magnetometer measurement */ - recipNorm = invSqrt(mx * mx + my * my + - mz * mz); - mx *= recipNorm; - my *= recipNorm; - mz *= recipNorm; - - /* Auxiliary variables to avoid repeated arithmetic */ - _2q0mx = 2.0f * q0 * mx; - _2q0my = 2.0f * q0 * my; - _2q0mz = 2.0f * q0 * mz; - _2q1mx = 2.0f * q1 * mx; - _2q0 = 2.0f * q0; - _2q1 = 2.0f * q1; - _2q2 = 2.0f * q2; - _2q3 = 2.0f * q3; - _2q0q2 = 2.0f * q0 * q2; - _2q2q3 = 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 = sqrt(hx * hx + hy * hy); - _2bz = -_2q0mx * q2 + _2q0my * q1 + mz * q0q0 + _2q1mx * q3 - mz * q1q1 + _2q2 * my * q3 - mz * q2q2 + mz * q3q3; - _4bx = 2.0f * _2bx; - _4bz = 2.0f * _2bz; - - /* Gradient decent algorithm corrective step */ - s0 = -_2q2 * (2.0f * q1q3 - _2q0q2 - ax) + _2q1 * (2.0f * q0q1 + _2q2q3 - ay) - _2bz * q2 * (_2bx * (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 * (0.5f - q1q1 - q2q2) - mz); - s1 = _2q3 * (2.0f * q1q3 - _2q0q2 - ax) + _2q0 * (2.0f * q0q1 + _2q2q3 - ay) - 4.0f * q1 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + _2bz * q3 * (_2bx * (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 * (0.5f - q1q1 - q2q2) - mz); - s2 = -_2q0 * (2.0f * q1q3 - _2q0q2 - ax) + _2q3 * (2.0f * q0q1 + _2q2q3 - ay) - 4.0f * q2 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + (-_4bx * q2 - _2bz * q0) * (_2bx * (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 * (0.5f - q1q1 - q2q2) - mz); - s3 = _2q1 * (2.0f * q1q3 - _2q0q2 - ax) + _2q2 * (2.0f * q0q1 + _2q2q3 - ay) + (-_4bx * q3 + _2bz * q1) * (_2bx * (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 * (0.5f - q1q1 - q2q2) - mz); - - /* normalize step magnitude */ - recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); - s0 *= recipNorm; - s1 *= recipNorm; - s2 *= recipNorm; - s3 *= recipNorm; - - /* Apply feedback step */ - qDot1 -= betaDef * s0; - qDot2 -= betaDef * s1; - qDot3 -= betaDef * s2; - qDot4 -= betaDef * s3; - } - - /* Integrate rate of change of quaternion to yield quaternion */ - q0 += qDot1 * (1.0f / sampleFreq); - q1 += qDot2 * (1.0f / sampleFreq); - q2 += qDot3 * (1.0f / sampleFreq); - q3 += qDot4 * (1.0f / sampleFreq); - - /* Normalise quaternion */ - recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); - q0 *= recipNorm; - q1 *= recipNorm; - q2 *= recipNorm; - q3 *= recipNorm; - - /* update quaternion in structure */ - quat->q0 = q0; - quat->q1 = q1; - quat->q2 = q2; - quat->q3 = q3; -} - -/* IMU algorithm update (does not take magneto in account) */ -void MadgwickAHRSupdateIMU(const struct imu_info *imu, struct quaternion *quat) -{ - 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; - float ax, ay, az, gx, gy, gz; - float q0, q1, q2, q3; - - /* use local variables, it's more readable */ - q0 = quat->q0; q1 = quat->q1; q2 = quat->q2; q3 = quat->q3; - gx = imu->gx; gy = imu->gy; gz = imu->gz; - ax = imu->ax; ay = imu->ay; az = imu->az; - - /* Rate of change of quaternion from gyroscope */ - qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); - qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); - qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); - qDot4 = 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 = 2.0f * q0; - _2q1 = 2.0f * q1; - _2q2 = 2.0f * q2; - _2q3 = 2.0f * q3; - _4q0 = 4.0f * q0; - _4q1 = 4.0f * q1; - _4q2 = 4.0f * q2; - _8q1 = 8.0f * q1; - _8q2 = 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 = 4.0f * q0q0 * q2 + _2q0 * ax + _4q2 * q3q3 - _2q3 * ay - _4q2 + _8q2 * q1q1 + _8q2 * q2q2 + _4q2 * az; - s3 = 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 -= betaDef * s0; - qDot2 -= betaDef * s1; - qDot3 -= betaDef * s2; - qDot4 -= betaDef * s3; - } - - /* Integrate rate of change of quaternion to yield quaternion */ - q0 += qDot1 * (1.0f / sampleFreq); - q1 += qDot2 * (1.0f / sampleFreq); - q2 += qDot3 * (1.0f / sampleFreq); - q3 += qDot4 * (1.0f / sampleFreq); - - /* Normalise quaternion */ - recipNorm = invSqrt(q0 * q0 + q1 * q1 + - q2 * q2 + q3 * q3); - q0 *= recipNorm; - q1 *= recipNorm; - q2 *= recipNorm; - q3 *= recipNorm; - - /* update quaternion in structure */ - quat->q0 = q0; - quat->q1 = q1; - quat->q2 = q2; - quat->q3 = q3; -} - +/* + * Copyright (c) 2014, Olivier MATZ + * Copyright (c) 2011-2012, SOH Madgwick + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +//============================================================================ +// MadgwickAHRS.c +//============================================================================ +// +// Implementation of Madgwick's IMU and AHRS algorithms. +// See: http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms +// +// 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 +// +//============================================================================ + +#include "MadgwickAHRS.h" +#include + +//#define sampleFreq 512.0f // sample frequency in Hz +//#define sampleFreq 46.0f // sample frequency in Hz +#define sampleFreq 85.0f // sample frequency in Hz +#define betaDef 0.1f // 2 * proportional gain + +static float invSqrt(float x) +{ + return 1.0f / sqrtf(x); +} + +/* AHRS algorithm update */ +void MadgwickAHRSupdate(const struct imu_info *imu, struct quaternion *quat) +{ + float recipNorm; + float s0, s1, s2, s3; + float qDot1, qDot2, qDot3, qDot4; + float hx, hy; + float _2q0mx, _2q0my, _2q0mz, _2q1mx, _2bx, _2bz, _4bx, _4bz; + float _2q0, _2q1, _2q2, _2q3, _2q0q2, _2q2q3, q0q0, q0q1, q0q2, q0q3; + float q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; + float mx, my, mz, ax, ay, az, gx, gy, gz; + float q0, q1, q2, q3; + + /* Use IMU algorithm if magnetometer measurement invalid (avoids NaN in + * magnetometer normalisation) */ + if ((imu->mx == 0.0f) && (imu->my == 0.0f) && (imu->mz == 0.0f)) { + MadgwickAHRSupdateIMU(imu, quat); + return; + } + + /* use local variables, it's more readable */ + q0 = quat->q0; q1 = quat->q1; q2 = quat->q2; q3 = quat->q3; + gx = imu->gx; gy = imu->gy; gz = imu->gz; + ax = imu->ax; ay = imu->ay; az = imu->az; + mx = imu->mx; my = imu->my; mz = imu->mz; + + /* Rate of change of quaternion from gyroscope */ + qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); + qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); + qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); + qDot4 = 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; + + /* Normalise magnetometer measurement */ + recipNorm = invSqrt(mx * mx + my * my + + mz * mz); + mx *= recipNorm; + my *= recipNorm; + mz *= recipNorm; + + /* Auxiliary variables to avoid repeated arithmetic */ + _2q0mx = 2.0f * q0 * mx; + _2q0my = 2.0f * q0 * my; + _2q0mz = 2.0f * q0 * mz; + _2q1mx = 2.0f * q1 * mx; + _2q0 = 2.0f * q0; + _2q1 = 2.0f * q1; + _2q2 = 2.0f * q2; + _2q3 = 2.0f * q3; + _2q0q2 = 2.0f * q0 * q2; + _2q2q3 = 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 = sqrt(hx * hx + hy * hy); + _2bz = -_2q0mx * q2 + _2q0my * q1 + mz * q0q0 + _2q1mx * q3 - mz * q1q1 + _2q2 * my * q3 - mz * q2q2 + mz * q3q3; + _4bx = 2.0f * _2bx; + _4bz = 2.0f * _2bz; + + /* Gradient decent algorithm corrective step */ + s0 = -_2q2 * (2.0f * q1q3 - _2q0q2 - ax) + _2q1 * (2.0f * q0q1 + _2q2q3 - ay) - _2bz * q2 * (_2bx * (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 * (0.5f - q1q1 - q2q2) - mz); + s1 = _2q3 * (2.0f * q1q3 - _2q0q2 - ax) + _2q0 * (2.0f * q0q1 + _2q2q3 - ay) - 4.0f * q1 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + _2bz * q3 * (_2bx * (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 * (0.5f - q1q1 - q2q2) - mz); + s2 = -_2q0 * (2.0f * q1q3 - _2q0q2 - ax) + _2q3 * (2.0f * q0q1 + _2q2q3 - ay) - 4.0f * q2 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + (-_4bx * q2 - _2bz * q0) * (_2bx * (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 * (0.5f - q1q1 - q2q2) - mz); + s3 = _2q1 * (2.0f * q1q3 - _2q0q2 - ax) + _2q2 * (2.0f * q0q1 + _2q2q3 - ay) + (-_4bx * q3 + _2bz * q1) * (_2bx * (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 * (0.5f - q1q1 - q2q2) - mz); + + /* normalize step magnitude */ + recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); + s0 *= recipNorm; + s1 *= recipNorm; + s2 *= recipNorm; + s3 *= recipNorm; + + /* Apply feedback step */ + qDot1 -= betaDef * s0; + qDot2 -= betaDef * s1; + qDot3 -= betaDef * s2; + qDot4 -= betaDef * s3; + } + + /* Integrate rate of change of quaternion to yield quaternion */ + q0 += qDot1 * (1.0f / sampleFreq); + q1 += qDot2 * (1.0f / sampleFreq); + q2 += qDot3 * (1.0f / sampleFreq); + q3 += qDot4 * (1.0f / sampleFreq); + + /* Normalise quaternion */ + recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); + q0 *= recipNorm; + q1 *= recipNorm; + q2 *= recipNorm; + q3 *= recipNorm; + + /* update quaternion in structure */ + quat->q0 = q0; + quat->q1 = q1; + quat->q2 = q2; + quat->q3 = q3; +} + +/* IMU algorithm update (does not take magneto in account) */ +void MadgwickAHRSupdateIMU(const struct imu_info *imu, struct quaternion *quat) +{ + 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; + float ax, ay, az, gx, gy, gz; + float q0, q1, q2, q3; + + /* use local variables, it's more readable */ + q0 = quat->q0; q1 = quat->q1; q2 = quat->q2; q3 = quat->q3; + gx = imu->gx; gy = imu->gy; gz = imu->gz; + ax = imu->ax; ay = imu->ay; az = imu->az; + + /* Rate of change of quaternion from gyroscope */ + qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); + qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); + qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); + qDot4 = 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 = 2.0f * q0; + _2q1 = 2.0f * q1; + _2q2 = 2.0f * q2; + _2q3 = 2.0f * q3; + _4q0 = 4.0f * q0; + _4q1 = 4.0f * q1; + _4q2 = 4.0f * q2; + _8q1 = 8.0f * q1; + _8q2 = 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 = 4.0f * q0q0 * q2 + _2q0 * ax + _4q2 * q3q3 - _2q3 * ay - _4q2 + _8q2 * q1q1 + _8q2 * q2q2 + _4q2 * az; + s3 = 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 -= betaDef * s0; + qDot2 -= betaDef * s1; + qDot3 -= betaDef * s2; + qDot4 -= betaDef * s3; + } + + /* Integrate rate of change of quaternion to yield quaternion */ + q0 += qDot1 * (1.0f / sampleFreq); + q1 += qDot2 * (1.0f / sampleFreq); + q2 += qDot3 * (1.0f / sampleFreq); + q3 += qDot4 * (1.0f / sampleFreq); + + /* Normalise quaternion */ + recipNorm = invSqrt(q0 * q0 + q1 * q1 + + q2 * q2 + q3 * q3); + q0 *= recipNorm; + q1 *= recipNorm; + q2 *= recipNorm; + q3 *= recipNorm; + + /* update quaternion in structure */ + quat->q0 = q0; + quat->q1 = q1; + quat->q2 = q2; + quat->q3 = q3; +} + diff --git a/imuboard/MadgwickAHRS.h b/imuboard/MadgwickAHRS.h index 018f34a..a613b99 100644 --- a/imuboard/MadgwickAHRS.h +++ b/imuboard/MadgwickAHRS.h @@ -1,46 +1,46 @@ -/* - * Copyright (c) 2014, Olivier MATZ - * Copyright (c) 2011, SOH Madgwick - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ - -//============================================================================= -// MadgwickAHRS.h -//============================================================================= -// -// Implementation of Madgwick's IMU and AHRS algorithms. -// See: http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms -// -// Date Author Notes -// 29/09/2011 SOH Madgwick Initial release -// 02/10/2011 SOH Madgwick Optimised for reduced CPU load -// -//============================================================================= - -#ifndef MadgwickAHRS_h -#define MadgwickAHRS_h - -#include "imu.h" - -extern volatile float beta; // algorithm gain - -/* update quaternion structure using the new IMU infos */ -void MadgwickAHRSupdate(const struct imu_info *imu, struct quaternion *quat); - -/* update quaternion structure using the new IMU infos, without using magneto */ -void MadgwickAHRSupdateIMU(const struct imu_info *imu, struct quaternion *quat); - -#endif +/* + * Copyright (c) 2014, Olivier MATZ + * Copyright (c) 2011, SOH Madgwick + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +//============================================================================= +// MadgwickAHRS.h +//============================================================================= +// +// Implementation of Madgwick's IMU and AHRS algorithms. +// See: http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms +// +// Date Author Notes +// 29/09/2011 SOH Madgwick Initial release +// 02/10/2011 SOH Madgwick Optimised for reduced CPU load +// +//============================================================================= + +#ifndef MadgwickAHRS_h +#define MadgwickAHRS_h + +#include "imu.h" + +extern volatile float beta; // algorithm gain + +/* update quaternion structure using the new IMU infos */ +void MadgwickAHRSupdate(const struct imu_info *imu, struct quaternion *quat); + +/* update quaternion structure using the new IMU infos, without using magneto */ +void MadgwickAHRSupdateIMU(const struct imu_info *imu, struct quaternion *quat); + +#endif -- 2.39.5