testListener.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 "tf/transform_listener.h"
31 #include "ros/ros.h"
32 
33 #include <gtest/gtest.h>
34 
35 TEST(TransformBroadcaster, single_frame)
36 {
38  EXPECT_TRUE(tfl.waitForTransform("frame1", "frame2", ros::Time(), ros::Duration(2.0)));
39 
40 }
41 
42 TEST(TransformBroadcaster, multi_frame)
43 {
45  EXPECT_TRUE(tfl.waitForTransform("vframe0", "vframe2", ros::Time(), ros::Duration(2.0)));
46 
47 }
48 
49 int main(int argc, char ** argv)
50 {
51  testing::InitGoogleTest(&argc, argv);
52 
53  //Initialize ROS
54  ros::init(argc, argv, "listener");
55  ros::NodeHandle nh;
56 
57  int ret = RUN_ALL_TESTS();
58 
59  return ret;
60 }
61 
int main(int argc, char **argv)
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
Block until a transform is possible or it times out.
Definition: tf.cpp:347
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
This class inherits from Transformer and automatically subscribes to ROS transform messages...
TEST(TransformBroadcaster, single_frame)


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Feb 28 2022 22:26:19