APM:Libraries
rotations.cpp
Go to the documentation of this file.
1 //
2 // Unit tests for the AP_Math rotations 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 
12 
13 static void print_vector(Vector3f &v)
14 {
15  hal.console->printf("[%.4f %.4f %.4f]\n",
16  (double)v.x,
17  (double)v.y,
18  (double)v.z);
19 }
20 
21 // test rotation method accuracy
22 static void test_rotation_accuracy(void)
23 {
24  Matrix3f attitude;
25  Vector3f small_rotation;
26  float roll, pitch, yaw;
27  float rot_angle;
28 
29  hal.console->printf("\nRotation method accuracy:\n");
30 
31  // test roll
32  for(int16_t i = 0; i < 90; i++ ) {
33 
34  // reset initial attitude
35  attitude.from_euler(0.0f, 0.0f, 0.0f);
36 
37  // calculate small rotation vector
38  rot_angle = ToRad(i);
39  small_rotation = Vector3f(rot_angle, 0.0f, 0.0f);
40 
41  // apply small rotation
42  attitude.rotate(small_rotation);
43 
44  // get resulting attitude's euler angles
45  attitude.to_euler(&roll, &pitch, &yaw);
46 
47  // now try via from_axis_angle
48  Matrix3f r2;
49  r2.from_axis_angle(Vector3f(1.0f, 0.0f, 0.0f), rot_angle);
50  attitude.from_euler(0.0f, 0.0f, 0.0f);
51  attitude = r2 * attitude;
52 
53  float roll2, pitch2, yaw2;
54  attitude.to_euler(&roll2, &pitch2, &yaw2);
55 
56  // display results
57  hal.console->printf("actual angle: %d angle1:%4.2f angle2:%4.2f\n",
58  (int)i,
59  (double)ToDeg(roll),
60  (double)ToDeg(roll2));
61  }
62 
63  // test pitch
64  for(int16_t i = 0; i < 90; i++ ) {
65 
66  // reset initial attitude
67  attitude.from_euler(0.0f, 0.0f, 0.0f);
68 
69  // calculate small rotation vector
70  rot_angle = ToRad(i);
71  small_rotation = Vector3f(0.0f ,rot_angle, 0.0f);
72 
73  // apply small rotation
74  attitude.rotate(small_rotation);
75 
76  // get resulting attitude's euler angles
77  attitude.to_euler(&roll, &pitch, &yaw);
78 
79  // now try via from_axis_angle
80  Matrix3f r2;
81  r2.from_axis_angle(Vector3f(0.0f ,1.0f, 0.0f), rot_angle);
82  attitude.from_euler(0.0f, 0.0f, 0.0f);
83  attitude = r2 * attitude;
84 
85  float roll2, pitch2, yaw2;
86  attitude.to_euler(&roll2, &pitch2, &yaw2);
87 
88  // display results
89  hal.console->printf("actual angle: %d angle1:%4.2f angle2:%4.2f\n",
90  (int)i,
91  (double)ToDeg(pitch),
92  (double)ToDeg(pitch2));
93  }
94 
95 
96  // test yaw
97  for(int16_t i = 0; i < 90; i++ ) {
98 
99  // reset initial attitude
100  attitude.from_euler(0.0f, 0.0f, 0.0f);
101 
102  // calculate small rotation vector
103  rot_angle = ToRad(i);
104  small_rotation = Vector3f(0.0f, 0.0f, rot_angle);
105 
106  // apply small rotation
107  attitude.rotate(small_rotation);
108 
109  // get resulting attitude's euler angles
110  attitude.to_euler(&roll, &pitch, &yaw);
111 
112  // now try via from_axis_angle
113  Matrix3f r2;
114  r2.from_axis_angle(Vector3f(0.0f, 0.0f, 1.0f), rot_angle);
115  attitude.from_euler(0.0f, 0.0f, 0.0f);
116  attitude = r2 * attitude;
117 
118  float roll2, pitch2, yaw2;
119  attitude.to_euler(&roll2, &pitch2, &yaw2);
120 
121  // display results
122  hal.console->printf("actual angle: %d angle1:%4.2f angle2:%4.2f\n",
123  (int)i,
124  (double)ToDeg(yaw),
125  (double)ToDeg(yaw2));
126  }
127 }
128 
129 static void test_euler(enum Rotation rotation, float roll, float pitch, float yaw)
130 {
131  Vector3f v, v1, v2, diff;
132  Matrix3f rotmat;
133  const float accuracy = 1.0e-6f;
134 
135  v.x = 1;
136  v.y = 2;
137  v.z = 3;
138  v1 = v;
139 
140  v1.rotate(rotation);
141 
142  rotmat.from_euler(radians(roll), radians(pitch), radians(yaw));
143  v2 = v;
144  v2 = rotmat * v2;
145 
146  diff = (v2 - v1);
147  if (diff.length() > accuracy) {
148  hal.console->printf("euler test %u failed : yaw:%d roll:%d pitch:%d\n",
149  (unsigned)rotation,
150  (int)yaw,
151  (int)roll,
152  (int)pitch);
153  hal.console->printf("fast rotated: ");
154  print_vector(v1);
155  hal.console->printf("slow rotated: ");
156  print_vector(v2);
157  hal.console->printf("\n");
158  }
159 }
160 
161 static void test_rotate_inverse(void)
162 {
163  hal.console->printf("\nrotate inverse test(Vector (1,1,1)):\n");
164  Vector3f vec(1.0f,1.0f,1.0f), cmp_vec(1.0f, 1.0f, 1.0f);
165  for (enum Rotation r = ROTATION_NONE;
166  r < ROTATION_MAX;
167  r = (enum Rotation)((uint8_t)r+1)) {
168  hal.console->printf("\nROTATION(%d) ", r);
169  vec.rotate(r);
170  print_vector(vec);
171 
172  hal.console->printf("INV_ROTATION(%d)", r);
173  vec.rotate_inverse(r);
174  print_vector(vec);
175  if ((vec - cmp_vec).length() > 1e-5) {
176  hal.console->printf("Rotation Test Failed!!! %.8f\n", (double)(vec - cmp_vec).length());
177  return;
178  }
179  }
180 }
181 static void test_eulers(void)
182 {
183  hal.console->printf("euler tests\n");
184  test_euler(ROTATION_NONE, 0, 0, 0);
185  test_euler(ROTATION_YAW_45, 0, 0, 45);
186  test_euler(ROTATION_YAW_90, 0, 0, 90);
187  test_euler(ROTATION_YAW_135, 0, 0, 135);
188  test_euler(ROTATION_YAW_180, 0, 0, 180);
189  test_euler(ROTATION_YAW_225, 0, 0, 225);
190  test_euler(ROTATION_YAW_270, 0, 0, 270);
191  test_euler(ROTATION_YAW_315, 0, 0, 315);
192  test_euler(ROTATION_ROLL_180, 180, 0, 0);
196  test_euler(ROTATION_PITCH_180, 0, 180, 0);
200  test_euler(ROTATION_ROLL_90, 90, 0, 0);
204  test_euler(ROTATION_ROLL_270, 270, 0, 0);
208  test_euler(ROTATION_PITCH_90, 0, 90, 0);
209  test_euler(ROTATION_PITCH_270, 0, 270, 0);
223 }
224 
225 static bool have_rotation(const Matrix3f &m)
226 {
227  Matrix3f mt = m.transposed();
228  for (enum Rotation r = ROTATION_NONE;
229  r < ROTATION_MAX;
230  r = (enum Rotation)((uint8_t)(r + 1))) {
231  Vector3f v(1.0f, 2.0f, 3.0f);
232  Vector3f v2 = v;
233  v2.rotate(r);
234  v2 = mt * v2;
235  if ((v2 - v).length() < 0.01f) {
236  return true;
237  }
238  }
239  return false;
240 }
241 
242 static void missing_rotations(void)
243 {
244  hal.console->printf("testing for missing rotations\n");
245  for (uint16_t yaw = 0; yaw < 360; yaw += 90)
246  for (uint16_t pitch = 0; pitch < 360; pitch += 90)
247  for (uint16_t roll = 0; roll < 360; roll += 90) {
248  Matrix3f m;
249  m.from_euler(ToRad(roll), ToRad(pitch), ToRad(yaw));
250  if (!have_rotation(m)) {
251  hal.console->printf("Missing rotation (%u, %u, %u)\n", roll, pitch, yaw);
252  }
253  }
254 }
255 
256 static void test_rotate_matrix(void)
257 {
258  for (enum Rotation r = ROTATION_NONE;
259  r < ROTATION_MAX;
260  r = (enum Rotation)((uint8_t)r+1)) {
261  //hal.console->printf("\nROTATION(%d)\n", r);
262  Vector3f vec(1,2,3);
263  Vector3f vec2 = vec;
264  vec.rotate(r);
265  Matrix3f m;
266  m.from_rotation(r);
267  vec2 = m * vec2;
268  //print_vector(vec);
269  //print_vector(vec2);
270  if ((vec - vec2).length() > 1e-5) {
271  hal.console->printf("Rotation Test Failed!!! %.8f\n", (double)(vec - vec2).length());
272  return;
273  }
274  }
275  hal.console->printf("test_rotate_matrix passed\n");
276 }
277 
278 
279 /*
280  * rotation tests
281  */
282 void setup(void)
283 {
284  hal.console->begin(115200);
285  hal.console->printf("rotation unit tests\n\n");
287  test_eulers();
291  hal.console->printf("rotation unit tests done\n\n");
292 }
293 
294 void loop(void) {}
295 
296 AP_HAL_MAIN();
void to_euler(float *roll, float *pitch, float *yaw) const
Definition: matrix3.cpp:49
static void missing_rotations(void)
Definition: rotations.cpp:242
Vector3< float > Vector3f
Definition: vector3.h:246
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: rotations.cpp:11
AP_HAL::UARTDriver * console
Definition: HAL.h:110
virtual void begin(uint32_t baud)=0
void from_axis_angle(const Vector3< T > &v, float theta)
Definition: matrix3.cpp:248
#define ToRad(x)
Definition: AP_Common.h:53
void setup()
Definition: rotations.cpp:282
AP_HAL_MAIN()
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
static void test_rotate_inverse(void)
Definition: rotations.cpp:161
Rotation
Definition: rotations.h:27
#define ToDeg(x)
Definition: AP_Common.h:54
Matrix3< T > transposed(void) const
Definition: matrix3.cpp:189
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
#define f(i)
T y
Definition: vector3.h:67
void loop()
Definition: rotations.cpp:294
T z
Definition: vector3.h:67
void from_rotation(enum Rotation rotation)
Definition: matrix3.cpp:63
static void test_eulers(void)
Definition: rotations.cpp:181
float v
Definition: Printf.cpp:15
const HAL & get_HAL()
float length(void) const
Definition: vector3.cpp:288
void rotate(enum Rotation rotation)
Definition: vector3.cpp:28
static void test_rotate_matrix(void)
Definition: rotations.cpp:256
static constexpr float radians(float deg)
Definition: AP_Math.h:158
static bool have_rotation(const Matrix3f &m)
Definition: rotations.cpp:225
static void print_vector(Vector3f &v)
Definition: rotations.cpp:13
static void test_rotation_accuracy(void)
Definition: rotations.cpp:22
void rotate(const Vector3< T > &g)
Definition: matrix3.cpp:115
static void test_euler(enum Rotation rotation, float roll, float pitch, float yaw)
Definition: rotations.cpp:129
T x
Definition: vector3.h:67