test_buffer_client.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2009, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of Willow Garage, Inc. nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 *********************************************************************/
37 #include <gtest/gtest.h>
38 #include <tf2_ros/buffer_client.h>
39 #include <ros/ros.h>
41 #include <tf2_kdl/tf2_kdl.h>
42 #include <tf2_bullet/tf2_bullet.h>
43 
44 static const double EPS = 1e-3;
45 
46 TEST(tf2_ros, buffer_client)
47 {
48  tf2_ros::BufferClient client("tf_action");
49 
50  //make sure that things are set up
51  ASSERT_TRUE(client.waitForServer(ros::Duration(4.0)));
52 
53  geometry_msgs::PointStamped p1;
54  p1.header.frame_id = "a";
55  p1.header.stamp = ros::Time();
56  p1.point.x = 0.0;
57  p1.point.y = 0.0;
58  p1.point.z = 0.0;
59 
60  try
61  {
62  geometry_msgs::PointStamped p2 = client.transform(p1, "b");
63  ROS_INFO("p1: (%.2f, %.2f, %.2f), p2: (%.2f, %.2f, %.2f)", p1.point.x,
64  p1.point.y, p1.point.z, p2.point.x, p2.point.y, p2.point.z);
65 
66  EXPECT_NEAR(p2.point.x, -5.0, EPS);
67  EXPECT_NEAR(p2.point.y, -6.0, EPS);
68  EXPECT_NEAR(p2.point.z, -7.0, EPS);
69  }
70  catch(tf2::TransformException& ex)
71  {
72  ROS_ERROR("Failed to transform: %s", ex.what());
73  ASSERT_FALSE("Should not get here");
74  }
75 }
76 
77 TEST(tf2_ros, buffer_client_different_types)
78 {
79  tf2_ros::BufferClient client("tf_action");
80 
81  //make sure that things are set up
82  ASSERT_TRUE(client.waitForServer(ros::Duration(4.0)));
83 
84  tf2::Stamped<KDL::Vector> k1(KDL::Vector(0, 0, 0), ros::Time(), "a");
85 
86  try
87  {
89  client.transform(k1, b1, "b");
90  ROS_INFO_STREAM("Bullet: (" << b1[0] << ", " << b1[1] << ", " << b1[2] << ")");
91  ROS_INFO_STREAM("KDL: (" << k1[0] << ", " << k1[1] << ", " << k1[2] << ")");
92  EXPECT_NEAR(b1[0], -5.0, EPS);
93  EXPECT_NEAR(b1[1], -6.0, EPS);
94  EXPECT_NEAR(b1[2], -7.0, EPS);
95  EXPECT_EQ(b1.frame_id_, "b");
96  EXPECT_EQ(k1.frame_id_, "a");
97  }
98  catch(tf2::TransformException& ex)
99  {
100  ROS_ERROR("Failed to transform: %s", ex.what());
101  ASSERT_FALSE("Should not get here");
102  }
103 }
104 
105 int main(int argc, char** argv)
106 {
107  testing::InitGoogleTest(&argc, argv);
108  ros::init(argc, argv, "buffer_client_test");
109  return RUN_ALL_TESTS();
110 }
111 
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static const double EPS
bool waitForServer(const ros::Duration &timeout=ros::Duration(0))
int main(int argc, char **argv)
#define ROS_INFO(...)
std::string frame_id_
#define ROS_INFO_STREAM(args)
T & transform(const T &in, T &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
TEST(tf2_ros, buffer_client)
#define ROS_ERROR(...)


test_tf2
Author(s): Tully Foote, Eitan Marder-Eppstein
autogenerated on Fri Oct 16 2020 19:09:05