Fang-Robotics-MCB
Fang Robotics Team Codebase
Loading...
Searching...
No Matches
MahonyAHRS.h
Go to the documentation of this file.
1//=============================================================================================
2// MahonyAHRS.h
3//=============================================================================================
4//
5// Madgwick's implementation of Mayhony's AHRS algorithm.
6// See: http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/
7//
8// From the x-io website "Open-source resources available on this website are
9// provided under the GNU General Public Licence unless an alternative licence
10// is provided in source."
11//
12// Date Author Notes
13// 29/09/2011 SOH Madgwick Initial release
14// 02/10/2011 SOH Madgwick Optimised for reduced CPU load
15// 09/06/2020 Matthew Arnold Update style, use safer casting
16// 04/30/2022 Matthew Arnold Change input/outputs from degrees to radians
17// 03/06/2025 Chinmay Murthy Make getters const
18//
19//=============================================================================================
20#ifndef MAHONY_AHRS_H_
21#define MAHONY_AHRS_H_
22
23#include <cmath>
24
25#include "modm/math/geometry/angle.hpp"
26
27//--------------------------------------------------------------------------------------------
28// Variable declaration
29
30class Mahony
31{
32private:
33 float twoKp; // 2 * proportional gain (Kp)
34 float twoKi; // 2 * integral gain (Ki)
35 float q0, q1, q2, q3; // quaternion of sensor frame relative to auxiliary frame
36 float integralFBx, integralFBy, integralFBz; // integral error terms scaled by Ki
37 float invSampleFreq;
38 float roll, pitch, yaw;
39 static float invSqrt(float x);
40 void computeAngles();
41
42 //-------------------------------------------------------------------------------------------
43 // Function declarations
44
45public:
46 Mahony();
47 void begin(float sampleFrequency, float kp, float ki)
48 {
49 invSampleFreq = 1.0f / sampleFrequency;
50 twoKp = 2.0f * kp;
51 twoKi = 2.0f * ki;
52 }
53 void reset()
54 {
55 q0 = 1.0f;
56 q1 = 0.0f;
57 q2 = 0.0f;
58 q3 = 0.0f;
59 integralFBx = 0.0f;
60 integralFBy = 0.0f;
61 integralFBz = 0.0f;
62 roll = 0.0f;
63 pitch = 0.0f;
64 yaw = 0.0f;
65 }
66 void update(
67 float gx,
68 float gy,
69 float gz,
70 float ax,
71 float ay,
72 float az,
73 float mx,
74 float my,
75 float mz);
76 void updateIMU(float gx, float gy, float gz, float ax, float ay, float az);
77 float getRoll() const { return roll; }
78 float getPitch() const { return pitch; }
79 float getYaw() const { return fmod(yaw + M_TWOPI, M_TWOPI); }
80};
81
82#endif // MAHONY_AHRS_H_
Definition MahonyAHRS.h:31
Mahony()
Definition MahonyAHRS.cpp:50
void update(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz)
Definition MahonyAHRS.cpp:67
float getPitch() const
Definition MahonyAHRS.h:78
void begin(float sampleFrequency, float kp, float ki)
Definition MahonyAHRS.h:47
float getRoll() const
Definition MahonyAHRS.h:77
void reset()
Definition MahonyAHRS.h:53
void updateIMU(float gx, float gy, float gz, float ax, float ay, float az)
Definition MahonyAHRS.cpp:191
float getYaw() const
Definition MahonyAHRS.h:79