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 #include <gtest/gtest.h>
00031 #include <tf2/buffer_core.h>
00032 #include "tf2/exceptions.h"
00033 #include <sys/time.h>
00034 #include <ros/ros.h>
00035 #include "rostest/permuter.h"
00036
00037 #include "tf2_ros/transform_listener.h"
00038
00039
00040 TEST(StaticTranformPublsher, a_b_different_times)
00041 {
00042 tf2::Buffer mB;
00043 tf2::TransformListener tfl(mB);
00044 EXPECT_TRUE(mB.canTransform("a", "b", ros::Time(), ros::Duration(1.0)));
00045 EXPECT_TRUE(mB.canTransform("a", "b", ros::Time(100), ros::Duration(1.0)));
00046 EXPECT_TRUE(mB.canTransform("a", "b", ros::Time(1000), ros::Duration(1.0)));
00047 };
00048
00049 TEST(StaticTranformPublsher, a_c_different_times)
00050 {
00051 tf2::Buffer mB;
00052 tf2::TransformListener tfl(mB);
00053 EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(), ros::Duration(1.0)));
00054 EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(100), ros::Duration(1.0)));
00055 EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(1000), ros::Duration(1.0)));
00056 };
00057
00058 TEST(StaticTranformPublsher, a_d_different_times)
00059 {
00060 tf2::Buffer mB;
00061 tf2::TransformListener tfl(mB);
00062 geometry_msgs::TransformStamped ts;
00063 ts.transform.rotation.w = 1;
00064 ts.header.frame_id = "c";
00065 ts.header.stamp = ros::Time(10.0);
00066 ts.child_frame_id = "d";
00067
00068
00069 EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(), ros::Duration(1.0)));
00070 EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(100), ros::Duration(1.0)));
00071 EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(1000), ros::Duration(1.0)));
00072
00073
00074 mB.setTransform(ts, "authority");
00075
00076 EXPECT_TRUE(mB.canTransform("c", "d", ros::Time(10), ros::Duration(0)));
00077
00078 EXPECT_TRUE(mB.canTransform("a", "d", ros::Time(), ros::Duration(0)));
00079 EXPECT_FALSE(mB.canTransform("a", "d", ros::Time(1), ros::Duration(0)));
00080 EXPECT_TRUE(mB.canTransform("a", "d", ros::Time(10), ros::Duration(0)));
00081 EXPECT_FALSE(mB.canTransform("a", "d", ros::Time(100), ros::Duration(0)));
00082
00083 };
00084
00085 int main(int argc, char **argv){
00086 testing::InitGoogleTest(&argc, argv);
00087 ros::init(argc, argv, "tf_unittest");
00088 return RUN_ALL_TESTS();
00089 }