23 #include "gtest/gtest.h" 31 std::uniform_real_distribution<float> angle_distribution(0.f, M_PI);
32 std::uniform_real_distribution<float> position_distribution(-1.f, 1.f);
34 for (
int i = 0; i != 100; ++i) {
35 const float angle = angle_distribution(rng);
36 const float x = position_distribution(rng);
37 const float y = position_distribution(rng);
38 const float z = position_distribution(rng);
39 const Eigen::Vector3f axis = Eigen::Vector3f(x, y, z).normalized();
42 Eigen::Vector3f(angle * axis)))),
47 TEST(TransformTest,
GetYaw) {
50 EXPECT_NEAR(1.2345,
GetYaw(rotation), 1e-9);
51 EXPECT_NEAR(-1.2345,
GetYaw(rotation.inverse()), 1e-9);
54 TEST(TransformTest, GetYawAxisOrdering) {
57 Eigen::AngleAxisd(0.4321, Eigen::Vector3d::UnitY()) *
58 Eigen::AngleAxisd(0.6789, Eigen::Vector3d::UnitX()));
59 EXPECT_NEAR(1.2345,
GetYaw(rotation), 1e-9);
63 const Rigid2d rigid2d({1., 2.}, 0.);
69 EXPECT_THAT(expected, IsNearly(rigid3d *
Embed3D(rigid2d), 1e-9));