33 #include <geometry_msgs/TransformStamped.h> 37 #include <gtest/gtest.h> 53 projected_frame_ = std::string(GetParam());
61 geometry_msgs::TransformStamped out;
70 ASSERT_EQ(out.transform.translation.x, 1);
71 ASSERT_EQ(out.transform.translation.y, 2);
72 ASSERT_EQ(out.transform.translation.z, 0);
73 ASSERT_NEAR(out.transform.rotation.x, 0, 1e-4);
74 ASSERT_NEAR(out.transform.rotation.y, 0, 1e-4);
75 ASSERT_NEAR(out.transform.rotation.z, 0.7071, 1e-4);
76 ASSERT_NEAR(out.transform.rotation.w, 0.7071, 1e-4);
77 ASSERT_EQ(out.header.frame_id,
"map");
84 "base_link_projected",
85 "base_link_projected2",
86 "base_link_tilt_projected"));
88 int main(
int argc,
char** argv)
90 testing::InitGoogleTest(&argc, argv);
91 ros::init(argc, argv,
"test_tf_projection_node");
93 return RUN_ALL_TESTS();
INSTANTIATE_TEST_CASE_P(ProjectionTransformInstance, TfProjectionTest,::testing::Values("base_link_projected","base_link_projected2","base_link_tilt_projected"))
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
tf2_ros::TransformListener tfl_
std::string projected_frame_
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &target_time, const ros::Duration timeout, std::string *errstr=NULL) const
int main(int argc, char **argv)
TEST_P(TfProjectionTest, ProjectionTransform)