00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <gtest/gtest.h>
00038 #include <tf2_ros/buffer_client.h>
00039 #include <ros/ros.h>
00040 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
00041 #include <tf2_kdl/tf2_kdl.h>
00042 #include <tf2_bullet/tf2_bullet.h>
00043
00044 static const double EPS = 1e-3;
00045
00046 TEST(tf2_ros, buffer_client)
00047 {
00048 tf2_ros::BufferClient client("tf_action");
00049
00050
00051 ASSERT_TRUE(client.waitForServer(ros::Duration(4.0)));
00052
00053 geometry_msgs::PointStamped p1;
00054 p1.header.frame_id = "a";
00055 p1.header.stamp = ros::Time();
00056 p1.point.x = 0.0;
00057 p1.point.y = 0.0;
00058 p1.point.z = 0.0;
00059
00060 try
00061 {
00062 geometry_msgs::PointStamped p2 = client.transform(p1, "b");
00063 ROS_INFO("p1: (%.2f, %.2f, %.2f), p2: (%.2f, %.2f, %.2f)", p1.point.x,
00064 p1.point.y, p1.point.z, p2.point.x, p2.point.y, p2.point.z);
00065
00066 EXPECT_NEAR(p2.point.x, -5.0, EPS);
00067 EXPECT_NEAR(p2.point.y, -6.0, EPS);
00068 EXPECT_NEAR(p2.point.z, -7.0, EPS);
00069 }
00070 catch(tf2::TransformException& ex)
00071 {
00072 ROS_ERROR("Failed to transform: %s", ex.what());
00073 ASSERT_FALSE("Should not get here");
00074 }
00075 }
00076
00077 TEST(tf2_ros, buffer_client_different_types)
00078 {
00079 tf2_ros::BufferClient client("tf_action");
00080
00081
00082 ASSERT_TRUE(client.waitForServer(ros::Duration(4.0)));
00083
00084 tf2::Stamped<KDL::Vector> k1(KDL::Vector(0, 0, 0), ros::Time(), "a");
00085
00086 try
00087 {
00088 tf2::Stamped<btVector3> b1;
00089 client.transform(k1, b1, "b");
00090 ROS_INFO_STREAM("Bullet: (" << b1[0] << ", " << b1[1] << ", " << b1[2] << ")");
00091 ROS_INFO_STREAM("KDL: (" << k1[0] << ", " << k1[1] << ", " << k1[2] << ")");
00092 EXPECT_NEAR(b1[0], -5.0, EPS);
00093 EXPECT_NEAR(b1[1], -6.0, EPS);
00094 EXPECT_NEAR(b1[2], -7.0, EPS);
00095 EXPECT_EQ(b1.frame_id_, "b");
00096 EXPECT_EQ(k1.frame_id_, "a");
00097 }
00098 catch(tf2::TransformException& ex)
00099 {
00100 ROS_ERROR("Failed to transform: %s", ex.what());
00101 ASSERT_FALSE("Should not get here");
00102 }
00103 }
00104
00105 int main(int argc, char** argv)
00106 {
00107 testing::InitGoogleTest(&argc, argv);
00108 ros::init(argc, argv, "buffer_client_test");
00109 return RUN_ALL_TESTS();
00110 }
00111