33 #include <tf2_kdl/tf2_kdl.h>
34 #include <kdl/frames_io.hpp>
35 #include <gtest/gtest.h>
40 static const double EPS = 1e-3;
49 EXPECT_NEAR(v_simple.p[0], -9,
EPS);
50 EXPECT_NEAR(v_simple.p[1], 18,
EPS);
51 EXPECT_NEAR(v_simple.p[2], 27,
EPS);
53 v_simple.M.GetRPY(r, p, y);
54 EXPECT_NEAR(r, 0.0,
EPS);
55 EXPECT_NEAR(p, 0.0,
EPS);
56 EXPECT_NEAR(y, 0.0,
EPS);
62 EXPECT_NEAR(v_advanced.p[0], -9,
EPS);
63 EXPECT_NEAR(v_advanced.p[1], 18,
EPS);
64 EXPECT_NEAR(v_advanced.p[2], 27,
EPS);
65 v_advanced.M.GetRPY(r, p, y);
66 EXPECT_NEAR(r, 0.0,
EPS);
67 EXPECT_NEAR(p, 0.0,
EPS);
68 EXPECT_NEAR(y, 0.0,
EPS);
81 EXPECT_NEAR(v_simple[0], -9,
EPS);
82 EXPECT_NEAR(v_simple[1], 18,
EPS);
83 EXPECT_NEAR(v_simple[2], 27,
EPS);
88 EXPECT_NEAR(v_advanced[0], -9,
EPS);
89 EXPECT_NEAR(v_advanced[1], 18,
EPS);
90 EXPECT_NEAR(v_advanced[2], 27,
EPS);
110 int main(
int argc,
char **argv){
111 testing::InitGoogleTest(&argc, argv);
118 geometry_msgs::TransformStamped t;
119 t.transform.translation.x = 10;
120 t.transform.translation.y = 20;
121 t.transform.translation.z = 30;
122 t.transform.rotation.x = 1;
124 t.header.frame_id =
"A";
125 t.child_frame_id =
"B";
128 int retval = RUN_ALL_TESTS();