time_reset_test.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2014, Open Source Robotics Foundation
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
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   // basic test
00064   ASSERT_FALSE(buffer.canTransform("foo", "bar", ros::Time(101, 0)));
00065 
00066   // set the transform
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   // make sure it arrives
00078   spin_for_a_second();
00079 
00080   // verify it's been set
00081   ASSERT_TRUE(buffer.canTransform("foo", "bar", ros::Time(101, 0)));
00082 
00083   c.clock = ros::Time(90);
00084   clock.publish(c);
00085 
00086   // make sure it arrives
00087   spin_for_a_second();
00088 
00089   //Send another message to trigger clock test on an unrelated frame
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   // make sure it arrives
00096   spin_for_a_second();
00097 
00098   //verify the data's been cleared
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 }


tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Thu Jun 6 2019 20:23:00