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 <tf2_ros/static_transform_broadcaster.h>
00034 #include <sys/time.h>
00035 #include <ros/ros.h>
00036 #include "rostest/permuter.h"
00037
00038 #include "tf2_ros/transform_listener.h"
00039
00040
00041 TEST(StaticTranformPublsher, a_b_different_times)
00042 {
00043 tf2_ros::Buffer mB;
00044 tf2_ros::TransformListener tfl(mB);
00045 EXPECT_TRUE(mB.canTransform("a", "b", ros::Time(), ros::Duration(1.0)));
00046 EXPECT_TRUE(mB.canTransform("a", "b", ros::Time(100), ros::Duration(1.0)));
00047 EXPECT_TRUE(mB.canTransform("a", "b", ros::Time(1000), ros::Duration(1.0)));
00048 };
00049
00050 TEST(StaticTranformPublsher, a_c_different_times)
00051 {
00052 tf2_ros::Buffer mB;
00053 tf2_ros::TransformListener tfl(mB);
00054 EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(), ros::Duration(1.0)));
00055 EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(100), ros::Duration(1.0)));
00056 EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(1000), ros::Duration(1.0)));
00057 };
00058
00059 TEST(StaticTranformPublsher, a_d_different_times)
00060 {
00061 tf2_ros::Buffer mB;
00062 tf2_ros::TransformListener tfl(mB);
00063 geometry_msgs::TransformStamped ts;
00064 ts.transform.rotation.w = 1;
00065 ts.header.frame_id = "c";
00066 ts.header.stamp = ros::Time(10.0);
00067 ts.child_frame_id = "d";
00068
00069
00070 EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(), ros::Duration(1.0)));
00071 EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(100), ros::Duration(1.0)));
00072 EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(1000), ros::Duration(1.0)));
00073
00074
00075 mB.setTransform(ts, "authority");
00076
00077 EXPECT_TRUE(mB.canTransform("c", "d", ros::Time(10), ros::Duration(0)));
00078
00079 EXPECT_TRUE(mB.canTransform("a", "d", ros::Time(), ros::Duration(0)));
00080 EXPECT_FALSE(mB.canTransform("a", "d", ros::Time(1), ros::Duration(0)));
00081 EXPECT_TRUE(mB.canTransform("a", "d", ros::Time(10), ros::Duration(0)));
00082 EXPECT_FALSE(mB.canTransform("a", "d", ros::Time(100), ros::Duration(0)));
00083
00084 };
00085
00086 TEST(StaticTranformPublsher, multiple_parent_test)
00087 {
00088 tf2_ros::Buffer mB;
00089 tf2_ros::TransformListener tfl(mB);
00090 tf2_ros::StaticTransformBroadcaster stb;
00091 geometry_msgs::TransformStamped ts;
00092 ts.transform.rotation.w = 1;
00093 ts.header.frame_id = "c";
00094 ts.header.stamp = ros::Time(10.0);
00095 ts.child_frame_id = "d";
00096
00097 stb.sendTransform(ts);
00098
00099
00100 EXPECT_TRUE(mB.canTransform("a", "d", ros::Time(), ros::Duration(1.0)));
00101 EXPECT_TRUE(mB.canTransform("a", "d", ros::Time(100), ros::Duration(1.0)));
00102 EXPECT_TRUE(mB.canTransform("a", "d", ros::Time(1000), ros::Duration(1.0)));
00103
00104
00105
00106 ts.header.frame_id = "new_parent";
00107 stb.sendTransform(ts);
00108 ts.child_frame_id = "other_child";
00109 stb.sendTransform(ts);
00110 ts.child_frame_id = "other_child2";
00111 stb.sendTransform(ts);
00112
00113 EXPECT_TRUE(mB.canTransform("new_parent", "d", ros::Time(), ros::Duration(1.0)));
00114 EXPECT_TRUE(mB.canTransform("new_parent", "other_child", ros::Time(), ros::Duration(1.0)));
00115 EXPECT_TRUE(mB.canTransform("new_parent", "other_child2", ros::Time(), ros::Duration(1.0)));
00116 EXPECT_FALSE(mB.canTransform("a", "d", ros::Time(), ros::Duration(1.0)));
00117 };
00118
00119 int main(int argc, char **argv){
00120 testing::InitGoogleTest(&argc, argv);
00121 ros::init(argc, argv, "tf_unittest");
00122 return RUN_ALL_TESTS();
00123 }