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_geometry_msgs/tf2_geometry_msgs.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
00043 TEST(TfGeometry, Frame)
00044 {
00045 geometry_msgs::PoseStamped v1;
00046 v1.pose.position.x = 1;
00047 v1.pose.position.y = 2;
00048 v1.pose.position.z = 3;
00049 v1.pose.orientation.x = 1;
00050 v1.header.stamp = ros::Time(2);
00051 v1.header.frame_id = "A";
00052
00053
00054 geometry_msgs::PoseStamped v_simple = tf_buffer->transform(v1, "B", ros::Duration(2.0));
00055 EXPECT_NEAR(v_simple.pose.position.x, -9, EPS);
00056 EXPECT_NEAR(v_simple.pose.position.y, 18, EPS);
00057 EXPECT_NEAR(v_simple.pose.position.z, 27, EPS);
00058 EXPECT_NEAR(v_simple.pose.orientation.x, 0.0, EPS);
00059 EXPECT_NEAR(v_simple.pose.orientation.y, 0.0, EPS);
00060 EXPECT_NEAR(v_simple.pose.orientation.z, 0.0, EPS);
00061 EXPECT_NEAR(v_simple.pose.orientation.w, 1.0, EPS);
00062
00063
00064
00065 geometry_msgs::PoseStamped v_advanced = tf_buffer->transform(v1, "B", ros::Time(2.0),
00066 "A", ros::Duration(3.0));
00067 EXPECT_NEAR(v_advanced.pose.position.x, -9, EPS);
00068 EXPECT_NEAR(v_advanced.pose.position.y, 18, EPS);
00069 EXPECT_NEAR(v_advanced.pose.position.z, 27, EPS);
00070 EXPECT_NEAR(v_advanced.pose.orientation.x, 0.0, EPS);
00071 EXPECT_NEAR(v_advanced.pose.orientation.y, 0.0, EPS);
00072 EXPECT_NEAR(v_advanced.pose.orientation.z, 0.0, EPS);
00073 EXPECT_NEAR(v_advanced.pose.orientation.w, 1.0, EPS);
00074 }
00075
00076
00077
00078 TEST(TfGeometry, Vector)
00079 {
00080 geometry_msgs::Vector3Stamped v1, res;
00081 v1.vector.x = 1;
00082 v1.vector.y = 2;
00083 v1.vector.z = 3;
00084 v1.header.stamp = ros::Time(2.0);
00085 v1.header.frame_id = "A";
00086
00087
00088 geometry_msgs::Vector3Stamped v_simple = tf_buffer->transform(v1, "B", ros::Duration(2.0));
00089 EXPECT_NEAR(v_simple.vector.x, 1, EPS);
00090 EXPECT_NEAR(v_simple.vector.y, -2, EPS);
00091 EXPECT_NEAR(v_simple.vector.z, -3, EPS);
00092
00093
00094 geometry_msgs::Vector3Stamped v_advanced = tf_buffer->transform(v1, "B", ros::Time(2.0),
00095 "A", ros::Duration(3.0));
00096 EXPECT_NEAR(v_advanced.vector.x, 1, EPS);
00097 EXPECT_NEAR(v_advanced.vector.y, -2, EPS);
00098 EXPECT_NEAR(v_advanced.vector.z, -3, EPS);
00099 }
00100
00101
00102 TEST(TfGeometry, Point)
00103 {
00104 geometry_msgs::PointStamped v1, res;
00105 v1.point.x = 1;
00106 v1.point.y = 2;
00107 v1.point.z = 3;
00108 v1.header.stamp = ros::Time(2.0);
00109 v1.header.frame_id = "A";
00110
00111
00112 geometry_msgs::PointStamped v_simple = tf_buffer->transform(v1, "B", ros::Duration(2.0));
00113 EXPECT_NEAR(v_simple.point.x, -9, EPS);
00114 EXPECT_NEAR(v_simple.point.y, 18, EPS);
00115 EXPECT_NEAR(v_simple.point.z, 27, EPS);
00116
00117
00118 geometry_msgs::PointStamped v_advanced = tf_buffer->transform(v1, "B", ros::Time(2.0),
00119 "A", ros::Duration(3.0));
00120 EXPECT_NEAR(v_advanced.point.x, -9, EPS);
00121 EXPECT_NEAR(v_advanced.point.y, 18, EPS);
00122 EXPECT_NEAR(v_advanced.point.z, 27, EPS);
00123 }
00124
00125
00126 int main(int argc, char **argv){
00127 testing::InitGoogleTest(&argc, argv);
00128 ros::init(argc, argv, "test");
00129 ros::NodeHandle n;
00130
00131 tf_buffer = new tf2::Buffer();
00132
00133
00134 geometry_msgs::TransformStamped t;
00135 t.transform.translation.x = 10;
00136 t.transform.translation.y = 20;
00137 t.transform.translation.z = 30;
00138 t.transform.rotation.x = 1;
00139 t.header.stamp = ros::Time(2.0);
00140 t.header.frame_id = "A";
00141 t.child_frame_id = "B";
00142 tf_buffer->setTransform(t, "test");
00143
00144 bool ret = RUN_ALL_TESTS();
00145 delete tf_buffer;
00146 return ret;
00147 }
00148
00149
00150
00151
00152