time_reset_test.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014, Open Source Robotics Foundation
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <gtest/gtest.h>
31 #include <thread>
32 #include <chrono>
35 #include <rosgraph_msgs/Clock.h>
36 
37 using namespace tf2;
38 
40 {
41  ros::spinOnce();
42  for (uint8_t i = 0; i < 10; ++i)
43  {
44  std::this_thread::sleep_for(std::chrono::microseconds(100));
45  ros::spinOnce();
46  }
47 }
48 
49 TEST(tf2_ros_transform_listener, time_backwards)
50 {
51 
52  tf2_ros::Buffer buffer;
53  tf2_ros::TransformListener tfl(buffer);
55 
57 
58  ros::Publisher clock = nh.advertise<rosgraph_msgs::Clock>("/clock", 5);
59 
60  rosgraph_msgs::Clock c;
61  c.clock = ros::Time(100);
62  clock.publish(c);
63 
64  // basic test
65  ASSERT_FALSE(buffer.canTransform("foo", "bar", ros::Time(101, 0)));
66 
67  // set the transform
68  geometry_msgs::TransformStamped msg;
69  msg.header.stamp = ros::Time(100, 0);
70  msg.header.frame_id = "foo";
71  msg.child_frame_id = "bar";
72  msg.transform.rotation.x = 1.0;
73  tfb.sendTransform(msg);
74  msg.header.stamp = ros::Time(102, 0);
75  tfb.sendTransform(msg);
76 
77 
78  // make sure it arrives
80 
81  // verify it's been set
82  ASSERT_TRUE(buffer.canTransform("foo", "bar", ros::Time(101, 0)));
83 
84  c.clock = ros::Time(90);
85  clock.publish(c);
86 
87  // make sure it arrives
89 
90  //Send another message to trigger clock test on an unrelated frame
91  msg.header.stamp = ros::Time(110, 0);
92  msg.header.frame_id = "foo2";
93  msg.child_frame_id = "bar2";
94  tfb.sendTransform(msg);
95 
96  // make sure it arrives
98 
99  //verify the data's been cleared
100  ASSERT_FALSE(buffer.canTransform("foo", "bar", ros::Time(101, 0)));
101 
102 }
103 
104 
105 
106 
107 int main(int argc, char **argv){
108  testing::InitGoogleTest(&argc, argv);
109  ros::init(argc, argv, "transform_listener_backwards_reset");
110  return RUN_ALL_TESTS();
111 }
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Standard implementation of the tf2_ros::BufferInterface abstract data type.
Definition: buffer.h:51
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &target_time, const ros::Duration timeout, std::string *errstr=NULL) const
Test if a transform is possible.
Definition: buffer.cpp:119
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void sendTransform(const geometry_msgs::TransformStamped &transform)
Send a StampedTransform The stamped data structure includes frame_id, and time, and parent_id already...
This class provides an easy way to request and receive coordinate frame transform information...
This class provides an easy way to publish coordinate frame transform information. It will handle all the messaging and stuffing of messages. And the function prototypes lay out all the necessary data needed for each message.
TEST(tf2_ros_transform_listener, time_backwards)
ROSCPP_DECL void spinOnce()
void spin_for_a_second()


tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Jun 27 2022 02:43:12