APM:Libraries
eulers.cpp
Go to the documentation of this file.
1 //
2 // Unit tests for the AP_Math euler code
3 //
4 
5 #include <AP_HAL/AP_HAL.h>
6 #include <AP_Math/AP_Math.h>
7 
8 void setup();
9 void loop();
10 void test_matrix_rotate(void);
11 void test_frame_transforms(void);
12 void test_conversions(void);
13 void test_quaternion_eulers(void);
14 void test_matrix_eulers(void);
15 
17 
18 #define SHOW_POLES_BREAKDOWN 0
19 
20 static float rad_diff(float rad1, float rad2)
21 {
22  float diff = rad1 - rad2;
23  if (diff > M_PI) {
24  diff -= 2 * M_PI;
25  }
26  if (diff < -M_PI) {
27  diff += 2 * M_PI;
28  }
29  return fabsf(diff);
30 }
31 
32 static void check_result(const char *msg,
33  float roll, float pitch, float yaw,
34  float roll2, float pitch2, float yaw2)
35 {
36  if (isnan(roll2) ||
37  isnan(pitch2) ||
38  isnan(yaw2)) {
39  hal.console->printf("%s NAN eulers roll=%f pitch=%f yaw=%f\n",
40  msg,
41  (double)roll,
42  (double)pitch,
43  (double)yaw);
44  }
45 
46  if (rad_diff(roll2,roll) > ToRad(179)) {
47  // reverse all 3
48  roll2 += fmodf(roll2 + M_PI, 2 * M_PI);
49  pitch2 += fmodf(pitch2 + M_PI, 2 * M_PI);
50  yaw2 += fmodf(yaw2 + M_PI, 2 * M_PI);
51  }
52 
53  if (rad_diff(roll2,roll) > 0.01f ||
54  rad_diff(pitch2, pitch) > 0.01f ||
55  rad_diff(yaw2, yaw) > 0.01f) {
56  if (pitch >= M_PI/2 ||
57  pitch <= -M_PI/2 ||
58  ToDeg(rad_diff(pitch, M_PI/2)) < 1 ||
59  ToDeg(rad_diff(pitch, -M_PI/2)) < 1) {
60  // we expect breakdown at these poles
61 #if SHOW_POLES_BREAKDOWN
62  hal.console->printf(
63  "%s breakdown eulers roll=%f/%f pitch=%f/%f yaw=%f/%f\n",
64  msg,
65  (double)ToDeg(roll), (double)ToDeg(roll2),
66  (double)ToDeg(pitch), (double)ToDeg(pitch2),
67  (double)ToDeg(yaw), (double)ToDeg(yaw2));
68 #endif
69  } else {
70  hal.console->printf(
71  "%s incorrect eulers roll=%f/%f pitch=%f/%f yaw=%f/%f\n",
72  msg,
73  (double)ToDeg(roll), (double)ToDeg(roll2),
74  (double)ToDeg(pitch), (double)ToDeg(pitch2),
75  (double)ToDeg(yaw), (double)ToDeg(yaw2));
76  }
77  }
78 }
79 
80 static void test_euler(float roll, float pitch, float yaw)
81 {
82  Matrix3f m;
83  float roll2, pitch2, yaw2;
84 
85  m.from_euler(roll, pitch, yaw);
86  m.to_euler(&roll2, &pitch2, &yaw2);
87  check_result("test_euler", roll, pitch, yaw, roll2, pitch2, yaw2);
88 }
89 
90 static const float angles[] = { 0, M_PI/8, M_PI/4, M_PI/2, M_PI,
91  -M_PI/8, -M_PI/4, -M_PI/2, -M_PI};
92 
94 {
95  uint8_t N = ARRAY_SIZE(angles);
96 
97  hal.console->printf("rotation matrix unit tests\n\n");
98 
99  for (uint8_t i = 0; i < N; i++)
100  for (uint8_t j = 0; j < N; j++)
101  for (uint8_t k = 0; k < N; k++)
102  test_euler(angles[i], angles[j], angles[k]);
103 
104  hal.console->printf("tests done\n\n");
105 }
106 
107 static void test_quaternion(float roll, float pitch, float yaw)
108 {
109  Quaternion q;
110  Matrix3f m;
111  float roll2, pitch2, yaw2;
112 
113  q.from_euler(roll, pitch, yaw);
114  q.to_euler(roll2, pitch2, yaw2);
115  check_result("test_quaternion1", roll, pitch, yaw, roll2, pitch2, yaw2);
116 
117  m.from_euler(roll, pitch, yaw);
118  m.to_euler(&roll2, &pitch2, &yaw2);
119  check_result("test_quaternion2", roll, pitch, yaw, roll2, pitch2, yaw2);
120 
121  m.from_euler(roll, pitch, yaw);
123  q.to_euler(roll2, pitch2, yaw2);
124  check_result("test_quaternion3", roll, pitch, yaw, roll2, pitch2, yaw2);
125 
126  q.rotation_matrix(m);
127  m.to_euler(&roll2, &pitch2, &yaw2);
128  check_result("test_quaternion4", roll, pitch, yaw, roll2, pitch2, yaw2);
129 }
130 
132 {
133  uint8_t N = ARRAY_SIZE(angles);
134 
135  hal.console->printf("quaternion unit tests\n\n");
136 
137  test_quaternion(M_PI/4, 0, 0);
138  test_quaternion(0, M_PI/4, 0);
139  test_quaternion(0, 0, M_PI/4);
140  test_quaternion(-M_PI/4, 0, 0);
141  test_quaternion(0, -M_PI/4, 0);
142  test_quaternion(0, 0, -M_PI/4);
143  test_quaternion(-M_PI/4, 1, 1);
144  test_quaternion(1, -M_PI/4, 1);
145  test_quaternion(1, 1, -M_PI/4);
146 
147  test_quaternion(ToRad(89), 0, 0.1f);
148  test_quaternion(0, ToRad(89), 0.1f);
149  test_quaternion(0.1f, 0, ToRad(89));
150 
151  test_quaternion(ToRad(91), 0, 0.1f);
152  test_quaternion(0, ToRad(91), 0.1f);
153  test_quaternion(0.1f, 0, ToRad(91));
154 
155  for (uint8_t i = 0; i < N; i++)
156  for (uint8_t j = 0; j < N; j++)
157  for (uint8_t k = 0; k < N; k++)
158  test_quaternion(angles[i], angles[j], angles[k]);
159 
160  hal.console->printf("tests done\n\n");
161 }
162 
163 
164 static void test_conversion(float roll, float pitch, float yaw)
165 {
166  Quaternion q;
167  Matrix3f m, m2;
168 
169  float roll2, pitch2, yaw2;
170  float roll3, pitch3, yaw3;
171 
172  q.from_euler(roll, pitch, yaw);
173  q.to_euler(roll2, pitch2, yaw2);
174  check_result("test_conversion1", roll, pitch, yaw, roll2, pitch2, yaw2);
175 
176  q.rotation_matrix(m);
177  m.to_euler(&roll2, &pitch2, &yaw2);
178 
179  m2.from_euler(roll, pitch, yaw);
180  m2.to_euler(&roll3, &pitch3, &yaw3);
181  if (m.is_nan()) {
182  hal.console->printf("NAN matrix roll=%f pitch=%f yaw=%f\n",
183  (double)roll,
184  (double)pitch,
185  (double)yaw);
186  }
187 
188  check_result("test_conversion2", roll, pitch, yaw, roll2, pitch2, yaw2);
189  check_result("test_conversion3", roll, pitch, yaw, roll3, pitch3, yaw3);
190 }
191 
193 {
194  uint8_t N = ARRAY_SIZE(angles);
195 
196  hal.console->printf("matrix/quaternion tests\n\n");
197 
198  test_conversion(1, 1.1f, 1.2f);
199  test_conversion(1, -1.1f, 1.2f);
200  test_conversion(1, -1.1f, -1.2f);
201  test_conversion(-1, 1.1f, -1.2f);
202  test_conversion(-1, 1.1f, 1.2f);
203 
204  for (uint8_t i = 0; i < N; i++)
205  for (uint8_t j = 0; j < N; j++)
206  for (uint8_t k = 0; k < N; k++)
207  test_conversion(angles[i], angles[j], angles[k]);
208 
209  hal.console->printf("tests done\n\n");
210 }
211 
213 {
214  Vector3f v, v2;
215  Quaternion q;
216  Matrix3f m;
217 
218  hal.console->printf("frame transform tests\n\n");
219 
220  q.from_euler(ToRad(45), ToRad(45), ToRad(45));
221  q.normalize();
222  m.from_euler(ToRad(45), ToRad(45), ToRad(45));
223 
224  v2 = v = Vector3f(0.0f, 0.0f, 1.0f);
225  q.earth_to_body(v2);
226  hal.console->printf("%f %f %f\n", (double)v2.x, (double)v2.y, (double)v2.z);
227  v2 = m * v;
228  hal.console->printf("%f %f %f\n\n", (double)v2.x, (double)v2.y, (double)v2.z);
229 
230  v2 = v = Vector3f(0.0f, 1.0f, 0.0f);
231  q.earth_to_body(v2);
232  hal.console->printf("%f %f %f\n", (double)v2.x, (double)v2.y, (double)v2.z);
233  v2 = m * v;
234  hal.console->printf("%f %f %f\n\n", (double)v2.x, (double)v2.y, (double)v2.z);
235 
236  v2 = v = Vector3f(1.0f, 0.0f, 0.0f);
237  q.earth_to_body(v2);
238  hal.console->printf("%f %f %f\n", (double)v2.x, (double)v2.y, (double)v2.z);
239  v2 = m * v;
240  hal.console->printf("%f %f %f\n", (double)v2.x, (double)v2.y, (double)v2.z);
241 }
242 
243 // generate a random float between -1 and 1
244 static float rand_num(void)
245 {
246  return ((2.0f * get_random16()) / 0xFFFF) - 1.0f;
247 }
248 
250 {
251  Matrix3f m1, m2, diff;
252  Vector3f r;
253 
254  m1.identity();
255  m2.identity();
256  r.x = rand_num();
257  r.y = rand_num();
258  r.z = rand_num();
259 
260  for (uint16_t i = 0; i < 1000; i++) {
261  // old method
262  Matrix3f temp_matrix;
263  temp_matrix.a.x = 0;
264  temp_matrix.a.y = -r.z;
265  temp_matrix.a.z = r.y;
266  temp_matrix.b.x = r.z;
267  temp_matrix.b.y = 0;
268  temp_matrix.b.z = -r.x;
269  temp_matrix.c.x = -r.y;
270  temp_matrix.c.y = r.x;
271  temp_matrix.c.z = 0;
272  temp_matrix = m1 * temp_matrix;
273  m1 += temp_matrix;
274 
275  // new method
276  m2.rotate(r);
277 
278  // check they behave in the same way
279  diff = m1 - m2;
280  float err = diff.a.length() + diff.b.length() + diff.c.length();
281 
282  if (err > 0) {
283  hal.console->printf("ERROR: i=%u err=%f\n", (unsigned)i, (double)err);
284  }
285  }
286 }
287 
288 /*
289  * euler angle tests
290  */
291 void setup(void)
292 {
293  hal.console->printf("euler unit tests\n\n");
294 
295  test_conversion(0, M_PI, 0);
296 
302 }
303 
304 void loop(void) {}
305 
306 AP_HAL_MAIN();
void to_euler(float &roll, float &pitch, float &yaw) const
Definition: quaternion.cpp:272
void to_euler(float *roll, float *pitch, float *yaw) const
Definition: matrix3.cpp:49
static float rad_diff(float rad1, float rad2)
Definition: eulers.cpp:20
void test_conversions(void)
Definition: eulers.cpp:192
static const float angles[]
Definition: eulers.cpp:90
Vector3< float > Vector3f
Definition: vector3.h:246
void setup()
Definition: eulers.cpp:291
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define ToRad(x)
Definition: AP_Common.h:53
void test_matrix_eulers(void)
Definition: eulers.cpp:93
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: eulers.cpp:16
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
void from_euler(float roll, float pitch, float yaw)
Definition: quaternion.cpp:130
static void test_conversion(float roll, float pitch, float yaw)
Definition: eulers.cpp:164
void from_rotation_matrix(const Matrix3f &m)
Definition: quaternion.cpp:76
void test_quaternion_eulers(void)
Definition: eulers.cpp:131
uint16_t get_random16(void)
Definition: AP_Math.cpp:212
void test_frame_transforms(void)
Definition: eulers.cpp:212
#define ToDeg(x)
Definition: AP_Common.h:54
void loop()
Definition: eulers.cpp:304
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
static void test_quaternion(float roll, float pitch, float yaw)
Definition: eulers.cpp:107
#define f(i)
T y
Definition: vector3.h:67
Vector3< T > c
Definition: matrix3.h:48
T z
Definition: vector3.h:67
bool is_nan(void)
Definition: matrix3.h:227
void rotation_matrix(Matrix3f &m) const
Definition: quaternion.cpp:24
float v
Definition: Printf.cpp:15
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
const HAL & get_HAL()
float length(void) const
Definition: vector3.cpp:288
static void test_euler(float roll, float pitch, float yaw)
Definition: eulers.cpp:80
static void check_result(const char *msg, float roll, float pitch, float yaw, float roll2, float pitch2, float yaw2)
Definition: eulers.cpp:32
void normalize()
Definition: quaternion.cpp:297
void test_matrix_rotate(void)
Definition: eulers.cpp:249
#define N
Vector3< T > b
Definition: matrix3.h:48
void rotate(const Vector3< T > &g)
Definition: matrix3.cpp:115
AP_HAL_MAIN()
#define M_PI
Definition: definitions.h:10
static float rand_num(void)
Definition: eulers.cpp:244
void earth_to_body(Vector3f &v) const
Definition: quaternion.cpp:122
Vector3< T > a
Definition: matrix3.h:48
void identity(void)
Definition: matrix3.h:219
T x
Definition: vector3.h:67