test_quat.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2016-2017, the mcl_3dl authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #define _USE_MATH_DEFINES
31 
32 #include <cstddef>
33 #include <cmath>
34 
35 #include <gtest/gtest.h>
36 
37 #include <mcl_3dl/quat.h>
38 
39 TEST(Quat, Constractors)
40 {
41  // Test quaternion elements style constructor and copy constructor
42  const mcl_3dl::Quat a(1.0, 2.0, 3.0, 4.0);
43  const mcl_3dl::Quat b(a);
44 
45  ASSERT_TRUE(a.x_ == 1.0);
46  ASSERT_TRUE(a.y_ == 2.0);
47  ASSERT_TRUE(a.z_ == 3.0);
48  ASSERT_TRUE(a.w_ == 4.0);
49  ASSERT_TRUE(b.x_ == 1.0);
50  ASSERT_TRUE(b.y_ == 2.0);
51  ASSERT_TRUE(b.z_ == 3.0);
52  ASSERT_TRUE(b.w_ == 4.0);
53 
54  // Test RPY and angle-axis style constructor
55  for (int i = 0; i < 3; ++i)
56  {
57  const float ang = M_PI / 2.0;
58  const float r = (i == 0) ? 1.0 : 0.0;
59  const float p = (i == 1) ? 1.0 : 0.0;
60  const float y = (i == 2) ? 1.0 : 0.0;
61 
62  // Check consistency between styles
63  const mcl_3dl::Quat c(mcl_3dl::Vec3(r * ang, p * ang, y * ang));
65  d.setRPY(mcl_3dl::Vec3(r * ang, p * ang, y * ang));
66  ASSERT_TRUE(c == d);
67 
68  const mcl_3dl::Quat e(mcl_3dl::Vec3(r, p, y), ang);
69  ASSERT_LT(fabs(c.x_ - e.x_), 1e-6);
70  ASSERT_LT(fabs(c.y_ - e.y_), 1e-6);
71  ASSERT_LT(fabs(c.z_ - e.z_), 1e-6);
72  ASSERT_LT(fabs(c.w_ - e.w_), 1e-6);
73 
74  // Check elements
75  ASSERT_LT(fabs(c.x_ - r * sqrtf(2.0) / 2.0), 1e-6);
76  ASSERT_LT(fabs(c.y_ - p * sqrtf(2.0) / 2.0), 1e-6);
77  ASSERT_LT(fabs(c.z_ - y * sqrtf(2.0) / 2.0), 1e-6);
78  ASSERT_LT(fabs(c.w_ - sqrtf(2.0) / 2.0), 1e-6);
79 
80  // Check reverse conversions
81  mcl_3dl::Vec3 crpy(c.getRPY());
82  ASSERT_LT(fabs(r * ang - crpy.x_), 1e-3);
83  ASSERT_LT(fabs(p * ang - crpy.y_), 1e-3);
84  ASSERT_LT(fabs(y * ang - crpy.z_), 1e-3);
85 
86  mcl_3dl::Vec3 axis;
87  float angle;
88  c.getAxisAng(axis, angle);
89  ASSERT_LT(fabs(r - axis.x_), 1e-6);
90  ASSERT_LT(fabs(p - axis.y_), 1e-6);
91  ASSERT_LT(fabs(y - axis.z_), 1e-6);
92  ASSERT_LT(fabs(ang - angle), 1e-6);
93  }
94 
95  // Test forward up style constructor
96  for (int i = 0; i < 3; ++i)
97  {
98  const mcl_3dl::Vec3 fw((i == 0) ? 1.0 : 0.0, (i == 1) ? 1.0 : 0.0, (i == 2) ? 1.0 : 0.0);
99  for (int j = 0; j < 3; ++j)
100  {
101  const mcl_3dl::Vec3 up((j == 0) ? 1.0 : 0.0, (j == 1) ? 1.0 : 0.0, (j == 2) ? 1.0 : 0.0);
102 
103  if (fw == up)
104  continue;
105 
106  const mcl_3dl::Quat q(fw, up);
107 
108  // Rotate forward and up vectors and validate
109  const mcl_3dl::Vec3 f = q * mcl_3dl::Vec3(1.0, 0.0, 0.0);
110  const mcl_3dl::Vec3 u = q * mcl_3dl::Vec3(0.0, 0.0, 1.0);
111 
112  ASSERT_LT(fabs(f.x_ - fw.x_), 1e-6);
113  ASSERT_LT(fabs(f.y_ - fw.y_), 1e-6);
114  ASSERT_LT(fabs(f.z_ - fw.z_), 1e-6);
115  ASSERT_LT(fabs(u.x_ - up.x_), 1e-6);
116  ASSERT_LT(fabs(u.y_ - up.y_), 1e-6);
117  ASSERT_LT(fabs(u.z_ - up.z_), 1e-6);
118  }
119  }
120 }
121 
122 TEST(Quat, Operators)
123 {
124  const mcl_3dl::Quat a(1.0, 2.0, 3.0, 4.0);
125 
126  // Test ==,!= operators
127  ASSERT_TRUE(mcl_3dl::Quat(1.0, 2.0, 3.0, 4.0) == a);
128  ASSERT_FALSE(mcl_3dl::Quat(1.0, 2.0, 3.0, 4.0) != a);
129 
130  for (uint32_t i = 1; i < (1 << 4); ++i)
131  {
132  const float xp = (i & (1 << 0)) ? 0.1 : 0.0;
133  const float yp = (i & (1 << 1)) ? 0.1 : 0.0;
134  const float zp = (i & (1 << 2)) ? 0.1 : 0.0;
135  const float wp = (i & (1 << 3)) ? 0.1 : 0.0;
136  ASSERT_TRUE(mcl_3dl::Quat(1.0 + xp, 2.0 + yp, 3.0 + zp, 4.0 + wp) != a);
137  ASSERT_FALSE(mcl_3dl::Quat(1.0 + xp, 2.0 + yp, 3.0 + zp, 4.0 + wp) == a);
138  }
139 
140  // Test +, -, +=, -= operators
141  const mcl_3dl::Quat adding(0.5, -0.5, 1.0, -1.0);
142  mcl_3dl::Quat a_plus = a;
143  mcl_3dl::Quat a_minus = a;
144  a_plus += adding;
145  a_minus -= adding;
146  ASSERT_TRUE(a + adding == mcl_3dl::Quat(1.5, 1.5, 4.0, 3.0));
147  ASSERT_TRUE(a + adding == a_plus);
148  ASSERT_TRUE(a - adding == mcl_3dl::Quat(0.5, 2.5, 2.0, 5.0));
149  ASSERT_TRUE(a - adding == a_minus);
150 
151  // Test -() operator
152  ASSERT_TRUE(-a == mcl_3dl::Quat(-1.0, -2.0, -3.0, -4.0));
153 
154  // Test scalar *, / operators
155  mcl_3dl::Quat a_mul = a;
156  mcl_3dl::Quat a_div = a;
157  a_mul *= 0.5;
158  a_div /= 2.0;
159  ASSERT_TRUE(a * 0.5 == mcl_3dl::Quat(0.5, 1.0, 1.5, 2.0));
160  ASSERT_TRUE(a / 2.0 == a * 0.5);
161  ASSERT_TRUE(a * 0.5 == a_mul);
162  ASSERT_TRUE(a / 2.0 == a_div);
163 }
164 
165 TEST(Quat, Norm)
166 {
167  // Check norm operations
168  const mcl_3dl::Quat a(1.0, 2.0, 3.0, 4.0);
169  const mcl_3dl::Quat b(-4.0, 5.0, 6.0, -7.0);
170  ASSERT_LT(fabs(a.norm() - 5.477226), 1e-6);
171  ASSERT_LT(fabs(b.norm() - 11.224972), 1e-6);
172  ASSERT_LT(fabs(a.normalized().norm() - 1.0), 1e-6);
173  ASSERT_LT(fabs(b.normalized().norm() - 1.0), 1e-6);
174 }
175 
176 TEST(Quat, Products)
177 {
178  // Check cross and dot products
179  const int num_samples = 8;
180  const mcl_3dl::Quat samples[num_samples] =
181  {
182  mcl_3dl::Quat(mcl_3dl::Vec3(1.5, 2.5, 3.5), 0.5),
183  mcl_3dl::Quat(mcl_3dl::Vec3(-0.5, 1.0, 1.0), 1.0),
184  mcl_3dl::Quat(mcl_3dl::Vec3(0.5, -1.0, 2.0), 1.5),
185  mcl_3dl::Quat(mcl_3dl::Vec3(0.5, 1.0, -2.0), 2.0),
186  mcl_3dl::Quat(mcl_3dl::Vec3(-2.0, -5.0, 4.0), 2.5),
187  mcl_3dl::Quat(mcl_3dl::Vec3(2.0, -5.0, -4.0), -1.0),
188  mcl_3dl::Quat(mcl_3dl::Vec3(-2.0, 5.0, -4.0), -1.5),
189  mcl_3dl::Quat(mcl_3dl::Vec3(-3.0, -1.0, -2.0), -2.0)
190  };
191 
192  // Check inverse
193  for (int i = 0; i < num_samples; ++i)
194  {
195  const mcl_3dl::Quat inv = samples[i].inv();
196  const mcl_3dl::Quat ident0 = inv * samples[i];
197  const mcl_3dl::Quat ident1 = samples[i] * inv;
198 
199  ASSERT_LT(fabs(ident0.x_), 1e-6);
200  ASSERT_LT(fabs(ident0.y_), 1e-6);
201  ASSERT_LT(fabs(ident0.z_), 1e-6);
202  ASSERT_LT(fabs(ident0.w_ - 1.0), 1e-6);
203  ASSERT_LT(fabs(ident1.x_), 1e-6);
204  ASSERT_LT(fabs(ident1.y_), 1e-6);
205  ASSERT_LT(fabs(ident1.z_), 1e-6);
206  ASSERT_LT(fabs(ident1.w_ - 1.0), 1e-6);
207  }
208 
209  // Check rotate axis
210  for (int i = 0; i < num_samples; ++i)
211  {
212  for (int j = 0; j < num_samples; ++j)
213  {
214  mcl_3dl::Vec3 a_axis;
215  float a_ang;
216  samples[i].getAxisAng(a_axis, a_ang);
217 
218  mcl_3dl::Quat a(a_axis, a_ang);
219  const mcl_3dl::Quat& b = samples[j];
220 
221  const mcl_3dl::Vec3 rotated_axis = b * a_axis;
222  a.rotateAxis(b);
223 
224  mcl_3dl::Vec3 a_axis2;
225  float a_ang2;
226  a.getAxisAng(a_axis2, a_ang2);
227 
228  ASSERT_LT(fabs(a_axis2.x_ - rotated_axis.x_), 1e-6);
229  ASSERT_LT(fabs(a_axis2.y_ - rotated_axis.y_), 1e-6);
230  ASSERT_LT(fabs(a_axis2.z_ - rotated_axis.z_), 1e-6);
231  ASSERT_LT(fabs(a_ang - a_ang2), 1e-6);
232  }
233  }
234 
235  // Check vector rotation
236  const int num_vecs = 3;
237  const mcl_3dl::Vec3 v[num_vecs] =
238  {
239  mcl_3dl::Vec3(1.0, 0.0, 0.0),
240  mcl_3dl::Vec3(0.0, 1.0, 0.0),
241  mcl_3dl::Vec3(0.0, 0.0, 1.0)
242  };
243  const int num_rots = 3;
244  const mcl_3dl::Quat r[num_rots] =
245  {
246  mcl_3dl::Quat(mcl_3dl::Vec3(1.0, 0.0, 0.0), M_PI / 2.0),
247  mcl_3dl::Quat(mcl_3dl::Vec3(0.0, 1.0, 0.0), -M_PI / 2.0),
248  mcl_3dl::Quat(mcl_3dl::Vec3(0.0, 0.0, 1.0), -M_PI / 2.0)
249  };
250  const mcl_3dl::Vec3 v_ans[3][3] =
251  {
252  mcl_3dl::Vec3(1.0, 0.0, 0.0),
253  mcl_3dl::Vec3(0.0, 0.0, 1.0),
254  mcl_3dl::Vec3(0.0, -1.0, 0.0),
255  mcl_3dl::Vec3(0.0, 0.0, 1.0),
256  mcl_3dl::Vec3(0.0, 1.0, 0.0),
257  mcl_3dl::Vec3(-1.0, 0.0, 0.0),
258  mcl_3dl::Vec3(0.0, -1.0, 0.0),
259  mcl_3dl::Vec3(1.0, 0.0, 0.0),
260  mcl_3dl::Vec3(0.0, 0.0, 1.0)
261  };
262  for (int i = 0; i < num_vecs; ++i)
263  {
264  for (int j = 0; j < num_rots; ++j)
265  {
266  const mcl_3dl::Vec3 result = r[j] * v[i];
267  ASSERT_LT(fabs(result.x_ - v_ans[j][i].x_), 1e-6);
268  ASSERT_LT(fabs(result.y_ - v_ans[j][i].y_), 1e-6);
269  ASSERT_LT(fabs(result.z_ - v_ans[j][i].z_), 1e-6);
270  }
271  }
272 
273  for (int i = 0; i < num_samples; ++i)
274  {
275  for (int j = 0; j < num_samples; ++j)
276  {
277  const mcl_3dl::Quat& a = samples[i];
278  const mcl_3dl::Quat& b = samples[j];
279 
280  // Check dot products based on the distributive property
281  ASSERT_LT((a - b).dot(a - b) - a.dot(a) - b.dot(b) + 2.0 * a.dot(b), 1e-6);
282 
283  // Check mcl_3dl::Quat by mcl_3dl::Quat products
284  const mcl_3dl::Vec3 v(1.0, 2.0, 3.0);
285  const mcl_3dl::Vec3 v1 = (a * b) * v;
286  const mcl_3dl::Vec3 v2 = a * (b * v);
287  ASSERT_LT(fabs(v1.x_ - v2.x_), 1e-6);
288  ASSERT_LT(fabs(v1.y_ - v2.y_), 1e-6);
289  ASSERT_LT(fabs(v1.z_ - v2.z_), 1e-6);
290  }
291  }
292 }
293 
294 int main(int argc, char** argv)
295 {
296  testing::InitGoogleTest(&argc, argv);
297 
298  return RUN_ALL_TESTS();
299 }
float z_
Definition: vec3.h:40
d
f
float y_
Definition: quat.h:43
int main(int argc, char **argv)
Definition: test_quat.cpp:294
TFSIMD_FORCE_INLINE const tfScalar & y() const
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
float w_
Definition: quat.h:45
float y_
Definition: vec3.h:39
void getAxisAng(Vec3 &axis, float &ang) const
Definition: quat.h:234
TEST(Quat, Constractors)
Definition: test_quat.cpp:39
Quat normalized() const
Definition: quat.h:172
Quat inv() const
Definition: quat.h:190
float dot(const Quat &q) const
Definition: quat.h:84
float x_
Definition: vec3.h:38
void setRPY(const Vec3 &rpy)
Definition: quat.h:210
Vec3 getRPY() const
Definition: quat.h:194
float norm() const
Definition: quat.h:88
float z_
Definition: quat.h:44
float x_
Definition: quat.h:42
void rotateAxis(const Quat &r)
Definition: quat.h:248


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 8 2019 03:32:36