Skip to content

Commit 50291dc

Browse files
committed
fix some error & update FactoryTest example
1 parent b7744ac commit 50291dc

File tree

19 files changed

+2843
-1703
lines changed

19 files changed

+2843
-1703
lines changed

examples/Basics/FactoryTest/include/cube.hpp

Lines changed: 323 additions & 309 deletions
Large diffs are not rendered by default.
Lines changed: 274 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,274 @@
1+
//=============================================================================================
2+
// MahonyAHRS.c
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+
//
16+
// Algorithm paper:
17+
// http://ieeexplore.ieee.org/xpl/login.jsp?tp=&arnumber=4608934&url=http%3A%2F%2Fieeexplore.ieee.org%2Fstamp%2Fstamp.jsp%3Ftp%3D%26arnumber%3D4608934
18+
//
19+
//=============================================================================================
20+
21+
//-------------------------------------------------------------------------------------------
22+
// Header files
23+
24+
#include "MahonyAHRS.h"
25+
#include <math.h>
26+
27+
//-------------------------------------------------------------------------------------------
28+
// Definitions
29+
30+
#define DEFAULT_SAMPLE_FREQ 512.0f // sample frequency in Hz
31+
#define twoKpDef (2.0f * 0.5f) // 2 * proportional gain
32+
#define twoKiDef (2.0f * 0.0f) // 2 * integral gain
33+
34+
35+
//============================================================================================
36+
// Functions
37+
38+
//-------------------------------------------------------------------------------------------
39+
// AHRS algorithm update
40+
41+
Mahony::Mahony()
42+
{
43+
twoKp = twoKpDef; // 2 * proportional gain (Kp)
44+
twoKi = twoKiDef; // 2 * integral gain (Ki)
45+
q0 = 1.0f;
46+
q1 = 0.0f;
47+
q2 = 0.0f;
48+
q3 = 0.0f;
49+
integralFBx = 0.0f;
50+
integralFBy = 0.0f;
51+
integralFBz = 0.0f;
52+
anglesComputed = 0;
53+
invSampleFreq = 1.0f / DEFAULT_SAMPLE_FREQ;
54+
}
55+
56+
void Mahony::update(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz)
57+
{
58+
float recipNorm;
59+
float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3;
60+
float hx, hy, bx, bz;
61+
float halfvx, halfvy, halfvz, halfwx, halfwy, halfwz;
62+
float halfex, halfey, halfez;
63+
float qa, qb, qc;
64+
65+
// Use IMU algorithm if magnetometer measurement invalid
66+
// (avoids NaN in magnetometer normalisation)
67+
if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) {
68+
updateIMU(gx, gy, gz, ax, ay, az);
69+
return;
70+
}
71+
72+
// Convert gyroscope degrees/sec to radians/sec
73+
gx *= 0.0174533f;
74+
gy *= 0.0174533f;
75+
gz *= 0.0174533f;
76+
77+
// Compute feedback only if accelerometer measurement valid
78+
// (avoids NaN in accelerometer normalisation)
79+
if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) {
80+
81+
// Normalise accelerometer measurement
82+
recipNorm = invSqrt(ax * ax + ay * ay + az * az);
83+
ax *= recipNorm;
84+
ay *= recipNorm;
85+
az *= recipNorm;
86+
87+
// Normalise magnetometer measurement
88+
recipNorm = invSqrt(mx * mx + my * my + mz * mz);
89+
mx *= recipNorm;
90+
my *= recipNorm;
91+
mz *= recipNorm;
92+
93+
// Auxiliary variables to avoid repeated arithmetic
94+
q0q0 = q0 * q0;
95+
q0q1 = q0 * q1;
96+
q0q2 = q0 * q2;
97+
q0q3 = q0 * q3;
98+
q1q1 = q1 * q1;
99+
q1q2 = q1 * q2;
100+
q1q3 = q1 * q3;
101+
q2q2 = q2 * q2;
102+
q2q3 = q2 * q3;
103+
q3q3 = q3 * q3;
104+
105+
// Reference direction of Earth's magnetic field
106+
hx = 2.0f * (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2));
107+
hy = 2.0f * (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1));
108+
bx = sqrtf(hx * hx + hy * hy);
109+
bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2));
110+
111+
// Estimated direction of gravity and magnetic field
112+
halfvx = q1q3 - q0q2;
113+
halfvy = q0q1 + q2q3;
114+
halfvz = q0q0 - 0.5f + q3q3;
115+
halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2);
116+
halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3);
117+
halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2);
118+
119+
// Error is sum of cross product between estimated direction
120+
// and measured direction of field vectors
121+
halfex = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy);
122+
halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz);
123+
halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx);
124+
125+
// Compute and apply integral feedback if enabled
126+
if(twoKi > 0.0f) {
127+
// integral error scaled by Ki
128+
integralFBx += twoKi * halfex * invSampleFreq;
129+
integralFBy += twoKi * halfey * invSampleFreq;
130+
integralFBz += twoKi * halfez * invSampleFreq;
131+
gx += integralFBx; // apply integral feedback
132+
gy += integralFBy;
133+
gz += integralFBz;
134+
} else {
135+
integralFBx = 0.0f; // prevent integral windup
136+
integralFBy = 0.0f;
137+
integralFBz = 0.0f;
138+
}
139+
140+
// Apply proportional feedback
141+
gx += twoKp * halfex;
142+
gy += twoKp * halfey;
143+
gz += twoKp * halfez;
144+
}
145+
146+
// Integrate rate of change of quaternion
147+
gx *= (0.5f * invSampleFreq); // pre-multiply common factors
148+
gy *= (0.5f * invSampleFreq);
149+
gz *= (0.5f * invSampleFreq);
150+
qa = q0;
151+
qb = q1;
152+
qc = q2;
153+
q0 += (-qb * gx - qc * gy - q3 * gz);
154+
q1 += (qa * gx + qc * gz - q3 * gy);
155+
q2 += (qa * gy - qb * gz + q3 * gx);
156+
q3 += (qa * gz + qb * gy - qc * gx);
157+
158+
// Normalise quaternion
159+
recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
160+
q0 *= recipNorm;
161+
q1 *= recipNorm;
162+
q2 *= recipNorm;
163+
q3 *= recipNorm;
164+
anglesComputed = 0;
165+
}
166+
167+
//-------------------------------------------------------------------------------------------
168+
// IMU algorithm update
169+
170+
void Mahony::updateIMU(float gx, float gy, float gz, float ax, float ay, float az)
171+
{
172+
float recipNorm;
173+
float halfvx, halfvy, halfvz;
174+
float halfex, halfey, halfez;
175+
float qa, qb, qc;
176+
177+
// Convert gyroscope degrees/sec to radians/sec
178+
gx *= 0.0174533f;
179+
gy *= 0.0174533f;
180+
gz *= 0.0174533f;
181+
182+
// Compute feedback only if accelerometer measurement valid
183+
// (avoids NaN in accelerometer normalisation)
184+
if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) {
185+
186+
// Normalise accelerometer measurement
187+
recipNorm = invSqrt(ax * ax + ay * ay + az * az);
188+
ax *= recipNorm;
189+
ay *= recipNorm;
190+
az *= recipNorm;
191+
192+
// Estimated direction of gravity
193+
halfvx = q1 * q3 - q0 * q2;
194+
halfvy = q0 * q1 + q2 * q3;
195+
halfvz = q0 * q0 - 0.5f + q3 * q3;
196+
197+
// Error is sum of cross product between estimated
198+
// and measured direction of gravity
199+
halfex = (ay * halfvz - az * halfvy);
200+
halfey = (az * halfvx - ax * halfvz);
201+
halfez = (ax * halfvy - ay * halfvx);
202+
203+
// Compute and apply integral feedback if enabled
204+
if(twoKi > 0.0f) {
205+
// integral error scaled by Ki
206+
integralFBx += twoKi * halfex * invSampleFreq;
207+
integralFBy += twoKi * halfey * invSampleFreq;
208+
integralFBz += twoKi * halfez * invSampleFreq;
209+
gx += integralFBx; // apply integral feedback
210+
gy += integralFBy;
211+
gz += integralFBz;
212+
} else {
213+
integralFBx = 0.0f; // prevent integral windup
214+
integralFBy = 0.0f;
215+
integralFBz = 0.0f;
216+
}
217+
218+
// Apply proportional feedback
219+
gx += twoKp * halfex;
220+
gy += twoKp * halfey;
221+
gz += twoKp * halfez;
222+
}
223+
224+
// Integrate rate of change of quaternion
225+
gx *= (0.5f * invSampleFreq); // pre-multiply common factors
226+
gy *= (0.5f * invSampleFreq);
227+
gz *= (0.5f * invSampleFreq);
228+
qa = q0;
229+
qb = q1;
230+
qc = q2;
231+
q0 += (-qb * gx - qc * gy - q3 * gz);
232+
q1 += (qa * gx + qc * gz - q3 * gy);
233+
q2 += (qa * gy - qb * gz + q3 * gx);
234+
q3 += (qa * gz + qb * gy - qc * gx);
235+
236+
// Normalise quaternion
237+
recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
238+
q0 *= recipNorm;
239+
q1 *= recipNorm;
240+
q2 *= recipNorm;
241+
q3 *= recipNorm;
242+
anglesComputed = 0;
243+
}
244+
245+
//-------------------------------------------------------------------------------------------
246+
// Fast inverse square-root
247+
// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root
248+
249+
float Mahony::invSqrt(float x)
250+
{
251+
float halfx = 0.5f * x;
252+
union { float f; long l; } i;
253+
i.f = x;
254+
i.l = 0x5f3759df - (i.l >> 1);
255+
float y = i.f;
256+
y = y * (1.5f - (halfx * y * y));
257+
y = y * (1.5f - (halfx * y * y));
258+
return y;
259+
}
260+
261+
//-------------------------------------------------------------------------------------------
262+
263+
void Mahony::computeAngles()
264+
{
265+
roll = atan2f(q0*q1 + q2*q3, 0.5f - q1*q1 - q2*q2);
266+
pitch = asinf(-2.0f * (q1*q3 - q0*q2));
267+
yaw = atan2f(q1*q2 + q0*q3, 0.5f - q2*q2 - q3*q3);
268+
anglesComputed = 1;
269+
}
270+
271+
272+
//============================================================================================
273+
// END OF CODE
274+
//============================================================================================
Lines changed: 66 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,66 @@
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+
// Date Author Notes
9+
// 29/09/2011 SOH Madgwick Initial release
10+
// 02/10/2011 SOH Madgwick Optimised for reduced CPU load
11+
//
12+
//=============================================================================================
13+
#ifndef MahonyAHRS_h
14+
#define MahonyAHRS_h
15+
#include <math.h>
16+
17+
//--------------------------------------------------------------------------------------------
18+
// Variable declaration
19+
20+
class Mahony {
21+
private:
22+
float twoKp; // 2 * proportional gain (Kp)
23+
float twoKi; // 2 * integral gain (Ki)
24+
float q0, q1, q2, q3; // quaternion of sensor frame relative to auxiliary frame
25+
float integralFBx, integralFBy, integralFBz; // integral error terms scaled by Ki
26+
float invSampleFreq;
27+
float roll, pitch, yaw;
28+
char anglesComputed;
29+
static float invSqrt(float x);
30+
void computeAngles();
31+
32+
//-------------------------------------------------------------------------------------------
33+
// Function declarations
34+
35+
public:
36+
Mahony();
37+
void begin(float sampleFrequency) { invSampleFreq = 1.0f / sampleFrequency; }
38+
void update(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz);
39+
void updateIMU(float gx, float gy, float gz, float ax, float ay, float az);
40+
float getRoll() {
41+
if (!anglesComputed) computeAngles();
42+
return roll * 57.29578f;
43+
}
44+
float getPitch() {
45+
if (!anglesComputed) computeAngles();
46+
return pitch * 57.29578f;
47+
}
48+
float getYaw() {
49+
if (!anglesComputed) computeAngles();
50+
return yaw * 57.29578f + 180.0f;
51+
}
52+
float getRollRadians() {
53+
if (!anglesComputed) computeAngles();
54+
return roll;
55+
}
56+
float getPitchRadians() {
57+
if (!anglesComputed) computeAngles();
58+
return pitch;
59+
}
60+
float getYawRadians() {
61+
if (!anglesComputed) computeAngles();
62+
return yaw;
63+
}
64+
};
65+
66+
#endif

examples/Basics/FactoryTest/lib/infrared_tools/include/ir_timings.h

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -23,14 +23,14 @@ extern "C" {
2323
*
2424
*/
2525
#define NEC_LEADING_CODE_HIGH_US (9000)
26-
#define NEC_LEADING_CODE_LOW_US (4500)
27-
#define NEC_PAYLOAD_ONE_HIGH_US (560)
28-
#define NEC_PAYLOAD_ONE_LOW_US (1690)
26+
#define NEC_LEADING_CODE_LOW_US (4500)
27+
#define NEC_PAYLOAD_ONE_HIGH_US (560)
28+
#define NEC_PAYLOAD_ONE_LOW_US (1690)
2929
#define NEC_PAYLOAD_ZERO_HIGH_US (560)
30-
#define NEC_PAYLOAD_ZERO_LOW_US (560)
31-
#define NEC_REPEAT_CODE_HIGH_US (9000)
32-
#define NEC_REPEAT_CODE_LOW_US (2250)
33-
#define NEC_ENDING_CODE_HIGH_US (560)
30+
#define NEC_PAYLOAD_ZERO_LOW_US (560)
31+
#define NEC_REPEAT_CODE_HIGH_US (9000)
32+
#define NEC_REPEAT_CODE_LOW_US (2250)
33+
#define NEC_ENDING_CODE_HIGH_US (560)
3434

3535
/**
3636
* @brief Timings for RC5 protocol

0 commit comments

Comments
 (0)