34 #include <geometry_msgs/TransformStamped.h>
39 #include <gtest/gtest.h>
63 geometry_msgs::TransformStamped out;
73 if (projected_frame_ ==
"base_link_tilt_projected_with_aligned")
77 const tf2::Vector3 result = trans * tf2::Vector3(1, 2, 3);
78 ASSERT_NEAR(out.transform.translation.x, result[0], 1e-4);
82 ASSERT_NEAR(out.transform.translation.x, 1, 1e-4);
84 ASSERT_NEAR(out.transform.translation.y, 2, 1e-4);
85 ASSERT_NEAR(out.transform.translation.z, 0, 1e-4);
86 ASSERT_NEAR(out.transform.rotation.x, 0, 1e-4);
87 ASSERT_NEAR(out.transform.rotation.y, 0, 1e-4);
88 ASSERT_NEAR(out.transform.rotation.z, 0.7071, 1e-4);
89 ASSERT_NEAR(out.transform.rotation.w, 0.7071, 1e-4);
90 ASSERT_EQ(out.header.frame_id,
"map");
91 ASSERT_EQ(out.child_frame_id, projected_frame_);
97 "base_link_projected",
98 "base_link_projected2",
99 "base_link_tilt_projected",
100 "base_link_tilt_projected_with_aligned"));
102 int main(
int argc,
char** argv)
104 testing::InitGoogleTest(&argc, argv);
105 ros::init(argc, argv,
"test_tf_projection_node");
107 return RUN_ALL_TESTS();