15 #include <gtest/gtest.h>
24 void yprTest(
const T& t,
double yaw1,
double pitch1,
double roll1) {
25 double yaw2, pitch2, roll2;
29 EXPECT_NEAR(yaw1, yaw2,
epsilon);
30 EXPECT_NEAR(pitch1, pitch2,
epsilon);
31 EXPECT_NEAR(roll1, roll2,
epsilon);
43 double yaw1, pitch1, roll1;
45 KDL::Rotation::Quaternion(x, y, z, w).GetRPY(roll1, pitch1, yaw1);
48 geometry_msgs::Quaternion q;
49 q.x = x; q.y =y; q.z = z; q.w = w;
50 yprTest(q, yaw1, pitch1, roll1);
53 geometry_msgs::QuaternionStamped qst;
55 yprTest(qst, yaw1, pitch1, roll1);
62 yprTest(q, yaw1, pitch1, roll1);
67 yprTest(sq, yaw1, pitch1, roll1);
73 geometry_msgs::Transform
t;
74 t.translation.x = 0.1;
75 t.translation.y = 0.2;
76 t.translation.z = 0.3;
83 t = tf2::getTransformIdentity<geometry_msgs::Transform>();
85 EXPECT_EQ(
t.translation.x, 0);
86 EXPECT_EQ(
t.translation.y, 0);
87 EXPECT_EQ(
t.translation.z, 0);
88 EXPECT_EQ(
t.rotation.x, 0);
89 EXPECT_EQ(
t.rotation.y, 0);
90 EXPECT_EQ(
t.rotation.z, 0);
91 EXPECT_EQ(
t.rotation.w, 1);
94 int main(
int argc,
char** argv)
96 testing::InitGoogleTest(&argc, argv);
97 return RUN_ALL_TESTS();