37 #include <gtest/gtest.h>
44 static const double EPS = 1e-3;
53 geometry_msgs::PointStamped p1;
54 p1.header.frame_id =
"a";
62 geometry_msgs::PointStamped p2 = client.
transform(p1,
"b");
63 ROS_INFO(
"p1: (%.2f, %.2f, %.2f), p2: (%.2f, %.2f, %.2f)", p1.point.x,
64 p1.point.y, p1.point.z, p2.point.x, p2.point.y, p2.point.z);
66 EXPECT_NEAR(p2.point.x, -5.0,
EPS);
67 EXPECT_NEAR(p2.point.y, -6.0,
EPS);
68 EXPECT_NEAR(p2.point.z, -7.0,
EPS);
72 ROS_ERROR(
"Failed to transform: %s", ex.what());
73 ASSERT_FALSE(
"Should not get here");
90 ROS_INFO_STREAM(
"Bullet: (" << b1[0] <<
", " << b1[1] <<
", " << b1[2] <<
")");
91 ROS_INFO_STREAM(
"KDL: (" << k1[0] <<
", " << k1[1] <<
", " << k1[2] <<
")");
92 EXPECT_NEAR(b1[0], -5.0,
EPS);
93 EXPECT_NEAR(b1[1], -6.0,
EPS);
94 EXPECT_NEAR(b1[2], -7.0,
EPS);
100 ROS_ERROR(
"Failed to transform: %s", ex.what());
101 ASSERT_FALSE(
"Should not get here");
105 int main(
int argc,
char** argv)
107 testing::InitGoogleTest(&argc, argv);
108 ros::init(argc, argv,
"buffer_client_test");
109 return RUN_ALL_TESTS();