Go to the documentation of this file.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_ros/transform_broadcaster.h>
00032 #include <tf2_ros/transform_listener.h>
00033 #include <sys/time.h>
00034 #include <rosgraph_msgs/Clock.h>
00035
00036 using namespace tf2;
00037
00038 void spin_for_a_second()
00039 {
00040 ros::spinOnce();
00041 for (uint8_t i = 0; i < 10; ++i)
00042 {
00043 usleep(100);
00044 ros::spinOnce();
00045 }
00046 }
00047
00048 TEST(tf2_ros_transform_listener, time_backwards)
00049 {
00050
00051 tf2_ros::Buffer buffer;
00052 tf2_ros::TransformListener tfl(buffer);
00053 tf2_ros::TransformBroadcaster tfb;
00054
00055 ros::NodeHandle nh = ros::NodeHandle();
00056
00057 ros::Publisher clock = nh.advertise<rosgraph_msgs::Clock>("/clock", 5);
00058
00059 rosgraph_msgs::Clock c;
00060 c.clock = ros::Time(100);
00061 clock.publish(c);
00062
00063
00064 ASSERT_FALSE(buffer.canTransform("foo", "bar", ros::Time(101, 0)));
00065
00066
00067 geometry_msgs::TransformStamped msg;
00068 msg.header.stamp = ros::Time(100, 0);
00069 msg.header.frame_id = "foo";
00070 msg.child_frame_id = "bar";
00071 msg.transform.rotation.x = 1.0;
00072 tfb.sendTransform(msg);
00073 msg.header.stamp = ros::Time(102, 0);
00074 tfb.sendTransform(msg);
00075
00076
00077
00078 spin_for_a_second();
00079
00080
00081 ASSERT_TRUE(buffer.canTransform("foo", "bar", ros::Time(101, 0)));
00082
00083 c.clock = ros::Time(90);
00084 clock.publish(c);
00085
00086
00087 spin_for_a_second();
00088
00089
00090 msg.header.stamp = ros::Time(110, 0);
00091 msg.header.frame_id = "foo2";
00092 msg.child_frame_id = "bar2";
00093 tfb.sendTransform(msg);
00094
00095
00096 spin_for_a_second();
00097
00098
00099 ASSERT_FALSE(buffer.canTransform("foo", "bar", ros::Time(101, 0)));
00100
00101 }
00102
00103
00104
00105
00106 int main(int argc, char **argv){
00107 testing::InitGoogleTest(&argc, argv);
00108 ros::init(argc, argv, "transform_listener_backwards_reset");
00109 return RUN_ALL_TESTS();
00110 }