test_static_publisher.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
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 <tf2/buffer_core.h>
32 #include "tf2/exceptions.h"
34 #include <sys/time.h>
35 #include <ros/ros.h>
36 #include "rostest/permuter.h"
37 
39 
40 TEST(StaticTransformPublisher, a_b_different_times)
41 {
42  tf2_ros::Buffer mB;
44  EXPECT_TRUE(mB.canTransform("a", "b", ros::Time(), ros::Duration(1.0)));
45  EXPECT_TRUE(mB.canTransform("a", "b", ros::Time(100), ros::Duration(1.0)));
46  EXPECT_TRUE(mB.canTransform("a", "b", ros::Time(1000), ros::Duration(1.0)));
47 };
48 
49 TEST(StaticTransformPublisher, a_c_different_times)
50 {
51  tf2_ros::Buffer mB;
53  EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(), ros::Duration(1.0)));
54  EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(100), ros::Duration(1.0)));
55  EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(1000), ros::Duration(1.0)));
56 };
57 
58 TEST(StaticTransformPublisher, a_d_different_times)
59 {
60  tf2_ros::Buffer mB;
62  geometry_msgs::TransformStamped ts;
63  ts.transform.rotation.w = 1;
64  ts.header.frame_id = "c";
65  ts.header.stamp = ros::Time(10.0);
66  ts.child_frame_id = "d";
67 
68  // make sure listener has populated
69  EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(), ros::Duration(1.0)));
70  EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(100), ros::Duration(1.0)));
71  EXPECT_TRUE(mB.canTransform("a", "c", ros::Time(1000), ros::Duration(1.0)));
72 
73  mB.setTransform(ts, "authority");
74  //printf("%s\n", mB.allFramesAsString().c_str());
75  EXPECT_TRUE(mB.canTransform("c", "d", ros::Time(10), ros::Duration(0)));
76 
77  EXPECT_TRUE(mB.canTransform("a", "d", ros::Time(), ros::Duration(0)));
78  EXPECT_FALSE(mB.canTransform("a", "d", ros::Time(1), ros::Duration(0)));
79  EXPECT_TRUE(mB.canTransform("a", "d", ros::Time(10), ros::Duration(0)));
80  EXPECT_FALSE(mB.canTransform("a", "d", ros::Time(100), ros::Duration(0)));
81 };
82 
83 TEST(StaticTransformPublisher, multiple_parent_test)
84 {
85  tf2_ros::Buffer mB;
88  geometry_msgs::TransformStamped ts;
89  ts.transform.rotation.w = 1;
90  ts.header.frame_id = "c";
91  ts.header.stamp = ros::Time(10.0);
92  ts.child_frame_id = "d";
93 
94  stb.sendTransform(ts);
95 
96  // make sure listener has populated
97  EXPECT_TRUE(mB.canTransform("a", "d", ros::Time(), ros::Duration(1.0)));
98  EXPECT_TRUE(mB.canTransform("a", "d", ros::Time(100), ros::Duration(1.0)));
99  EXPECT_TRUE(mB.canTransform("a", "d", ros::Time(1000), ros::Duration(1.0)));
100 
101  // Publish new transform with child 'd', should replace old one in static tf
102  ts.header.frame_id = "new_parent";
103  stb.sendTransform(ts);
104  ts.child_frame_id = "other_child";
105  stb.sendTransform(ts);
106  ts.child_frame_id = "other_child2";
107  stb.sendTransform(ts);
108 
109  EXPECT_TRUE(mB.canTransform("new_parent", "d", ros::Time(), ros::Duration(1.0)));
110  EXPECT_TRUE(mB.canTransform("new_parent", "other_child", ros::Time(), ros::Duration(1.0)));
111  EXPECT_TRUE(mB.canTransform("new_parent", "other_child2", ros::Time(), ros::Duration(1.0)));
112  EXPECT_FALSE(mB.canTransform("a", "d", ros::Time(), ros::Duration(1.0)));
113 };
114 
115 TEST(StaticTransformPublisher, tf_from_param_server_valid)
116 {
117  // This TF is loaded from the parameter server; ensure it is valid.
118  tf2_ros::Buffer mB;
120  EXPECT_TRUE(mB.canTransform("robot_calibration", "world", ros::Time(), ros::Duration(1.0)));
121  EXPECT_TRUE(mB.canTransform("robot_calibration", "world", ros::Time(100), ros::Duration(1.0)));
122  EXPECT_TRUE(mB.canTransform("robot_calibration", "world", ros::Time(1000), ros::Duration(1.0)));
123 }
124 
125 int main(int argc, char **argv){
126  testing::InitGoogleTest(&argc, argv);
127  ros::init(argc, argv, "tf_unittest");
128  return RUN_ALL_TESTS();
129 }
bool setTransform(const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false)
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TEST(StaticTransformPublisher, a_b_different_times)
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
void sendTransform(const geometry_msgs::TransformStamped &transform)


test_tf2
Author(s): Tully Foote, Eitan Marder-Eppstein
autogenerated on Fri Jun 7 2019 21:45:56