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


test_tf2
Author(s): Tully Foote, Eitan Marder-Eppstein
autogenerated on Mon Jun 27 2022 02:43:28