14 #define ECL_USE_EIGEN3 1
20 #include <gtest/gtest.h>
23 #include "../../include/ecl/geometry/legacy_pose2d.hpp"
24 #include "../../include/ecl/geometry/legacy_pose3d.hpp"
32 using ecl::linear_algebra::AngleAxis;
33 using ecl::linear_algebra::Matrix3d;
34 using ecl::linear_algebra::Vector3d;
35 using ecl::linear_algebra::Quaternion;
36 using ecl::linear_algebra::Translation3d;
42 TEST(LegacyPose3DTests,constructors) {
45 Matrix3d zero_rotation = Matrix3d::Identity();
46 Vector3d zero_translation; zero_translation << 0.0,0.0,0.0;
49 EXPECT_TRUE(pose1.rotation().isApprox(zero_rotation,0.1));
50 EXPECT_TRUE(pose1.translation().isApprox(v,0.1));
52 result = pose2.rotation().block<2,2>(0,0).
isApprox(pose_2d.rotationMatrix(),0.1);
54 result = pose2.translation().segment<2>(0).
isApprox(pose_2d.translation(),0.1);
57 EXPECT_TRUE(pose3.rotation().isApprox(pose2.rotation(),0.1));
58 EXPECT_TRUE(pose3.translation().isApprox(v,0.1));
60 EXPECT_TRUE(pose4.rotation().isApprox(pose3.rotation(),0.1));
61 EXPECT_TRUE(pose4.translation().isApprox(pose3.translation(),0.1));
65 TEST(LegacyPose3DTests,assignment) {
73 EXPECT_TRUE(pose1.rotation().isApprox(rot,0.1));
74 EXPECT_TRUE(pose1.translation().isApprox(v,0.1));
76 EXPECT_TRUE(pose2.rotation().isApprox(rot,0.1));
77 EXPECT_TRUE(pose2.translation().isApprox(v,0.1));
80 TEST(LegacyPose3DTests,eigenStyle) {
88 EXPECT_TRUE(pose1.rotation().isApprox(rot,0.1));
89 EXPECT_TRUE(pose1.translation().isApprox(v,0.1));
91 TEST(LegacyPose3DTests,inverse) {
92 Vector3d z_axis; z_axis << 0.0, 0.0, 1.0;
94 Matrix3d rot = AngleAxis<double>(
ecl::pi/2.0,z_axis).toRotationMatrix();
95 Vector3d trans; trans << 1.0, 2.0, 3.0;
99 EXPECT_TRUE(Matrix3d::Identity().
isApprox(repose.rotation(),0.1));
100 for (
unsigned int i = 0; i < 3; ++i ) {
101 EXPECT_LT(zero[i],repose.translation()[i]+0.01);
102 EXPECT_GT(zero[i]+0.01,repose.translation()[i]);
106 TEST(LegacyPose3DTests,operators) {
107 Vector3d z_axis; z_axis << 0.0, 0.0, 1.0;
108 Matrix3d rot = AngleAxis<double>(
ecl::pi/2.0,z_axis).toRotationMatrix();
109 Matrix3d rot_pi = AngleAxis<double>(
ecl::pi,z_axis).toRotationMatrix();
110 Vector3d trans; trans << 1.0, 2.0, 3.0;
111 Vector3d expected_final_trans; expected_final_trans << -1.0, 3.0, 6.0;
114 EXPECT_TRUE(rot_pi.isApprox(final_pose.rotation()));
115 EXPECT_TRUE(expected_final_trans.isApprox(final_pose.translation()));
117 EXPECT_TRUE(rot_pi.isApprox(pose.rotation()));
118 EXPECT_TRUE(expected_final_trans.isApprox(pose.translation()));
125 int main(
int argc,
char **argv) {
126 testing::InitGoogleTest(&argc,argv);
127 return RUN_ALL_TESTS();