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
00033 #include <tf2_bullet/tf2_bullet.h>
00034 #include <tf2_ros/transform_listener.h>
00035 #include <ros/ros.h>
00036 #include <gtest/gtest.h>
00037
00038
00039 tf2::Buffer* tf_buffer;
00040 static const double EPS = 1e-3;
00041
00042 TEST(TfBullet, Transform)
00043 {
00044 tf2::Stamped<btTransform> v1(btTransform(btQuaternion(1,0,0,0), btVector3(1,2,3)), ros::Time(2.0), "A");
00045
00046
00047 btTransform v_simple = tf_buffer->transform(v1, "B", ros::Duration(2.0));
00048 EXPECT_NEAR(v_simple.getOrigin().getX(), -9, EPS);
00049 EXPECT_NEAR(v_simple.getOrigin().getY(), 18, EPS);
00050 EXPECT_NEAR(v_simple.getOrigin().getZ(), 27, EPS);
00051
00052
00053 btTransform v_advanced = tf_buffer->transform(v1, "B", ros::Time(2.0),
00054 "B", ros::Duration(3.0));
00055 EXPECT_NEAR(v_advanced.getOrigin().getX(), -9, EPS);
00056 EXPECT_NEAR(v_advanced.getOrigin().getY(), 18, EPS);
00057 EXPECT_NEAR(v_advanced.getOrigin().getZ(), 27, EPS);
00058 }
00059
00060
00061
00062 TEST(TfBullet, Vector)
00063 {
00064 tf2::Stamped<btVector3> v1(btVector3(1,2,3), ros::Time(2.0), "A");
00065
00066
00067 btVector3 v_simple = tf_buffer->transform(v1, "B", ros::Duration(2.0));
00068 EXPECT_NEAR(v_simple.getX(), -9, EPS);
00069 EXPECT_NEAR(v_simple.getY(), 18, EPS);
00070 EXPECT_NEAR(v_simple.getZ(), 27, EPS);
00071
00072
00073 btVector3 v_advanced = tf_buffer->transform(v1, "B", ros::Time(2.0),
00074 "B", ros::Duration(3.0));
00075 EXPECT_NEAR(v_advanced.getX(), -9, EPS);
00076 EXPECT_NEAR(v_advanced.getY(), 18, EPS);
00077 EXPECT_NEAR(v_advanced.getZ(), 27, EPS);
00078 }
00079
00080 TEST(TfBullet, ConvertVector)
00081 {
00082 btVector3 v(1,2,3);
00083
00084 btVector3 v1 = v;
00085 tf2::convert(v1, v1);
00086
00087 EXPECT_EQ(v, v1);
00088
00089 btVector3 v2(3,4,5);
00090 tf2::convert(v1, v2);
00091
00092 EXPECT_EQ(v, v2);
00093 EXPECT_EQ(v1, v2);
00094 }
00095
00096
00097
00098 int main(int argc, char **argv){
00099 testing::InitGoogleTest(&argc, argv);
00100 ros::init(argc, argv, "test");
00101 ros::NodeHandle n;
00102
00103 tf_buffer = new tf2::Buffer();
00104
00105
00106 geometry_msgs::TransformStamped t;
00107 t.transform.translation.x = 10;
00108 t.transform.translation.y = 20;
00109 t.transform.translation.z = 30;
00110 t.transform.rotation.x = 1;
00111 t.header.stamp = ros::Time(2.0);
00112 t.header.frame_id = "A";
00113 t.child_frame_id = "B";
00114 tf_buffer->setTransform(t, "test");
00115
00116 bool ret = RUN_ALL_TESTS();
00117 delete tf_buffer;
00118 return ret;
00119 }