30 #define _USE_MATH_DEFINES 35 #include <gtest/gtest.h> 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);
55 for (
int i = 0; i < 3; ++i)
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;
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);
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);
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);
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);
96 for (
int i = 0; i < 3; ++i)
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)
101 const mcl_3dl::Vec3 up((j == 0) ? 1.0 : 0.0, (j == 1) ? 1.0 : 0.0, (j == 2) ? 1.0 : 0.0);
110 const mcl_3dl::Vec3 u = q * mcl_3dl::Vec3(0.0, 0.0, 1.0);
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);
130 for (uint32_t i = 1; i < (1 << 4); ++i)
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);
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);
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);
170 ASSERT_LT(fabs(a.
norm() - 5.477226), 1e-6);
171 ASSERT_LT(fabs(b.
norm() - 11.224972), 1e-6);
179 const int num_samples = 8;
193 for (
int i = 0; i < num_samples; ++i)
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);
210 for (
int i = 0; i < num_samples; ++i)
212 for (
int j = 0; j < num_samples; ++j)
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);
236 const int num_vecs = 3;
243 const int num_rots = 3;
262 for (
int i = 0; i < num_vecs; ++i)
264 for (
int j = 0; j < num_rots; ++j)
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);
273 for (
int i = 0; i < num_samples; ++i)
275 for (
int j = 0; j < num_samples; ++j)
281 ASSERT_LT((a - b).
dot(a - b) - a.
dot(a) - b.
dot(b) + 2.0 * a.
dot(b), 1e-6);
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);
294 int main(
int argc,
char** argv)
296 testing::InitGoogleTest(&argc, argv);
298 return RUN_ALL_TESTS();
int main(int argc, char **argv)
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)
void getAxisAng(Vec3 &axis, float &ang) const
float dot(const Quat &q) const
void setRPY(const Vec3 &rpy)
void rotateAxis(const Quat &r)