test_tf2_bullet.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 
33 #include <tf2_bullet/tf2_bullet.h>
34 #include <tf2_ros/buffer.h>
35 #include <ros/ros.h>
36 #include <gtest/gtest.h>
37 #include <tf2/convert.h>
38 
40 static const double EPS = 1e-3;
41 
42 TEST(TfBullet, Transform)
43 {
44  tf2::Stamped<btTransform> v1(btTransform(btQuaternion(1,0,0,0), btVector3(1,2,3)), ros::Time(2.0), "A");
45 
46  // simple api
47  btTransform v_simple = tf_buffer->transform(v1, "B", ros::Duration(2.0));
48  EXPECT_NEAR(v_simple.getOrigin().getX(), -9, EPS);
49  EXPECT_NEAR(v_simple.getOrigin().getY(), 18, EPS);
50  EXPECT_NEAR(v_simple.getOrigin().getZ(), 27, EPS);
51 
52  // advanced api
53  btTransform v_advanced = tf_buffer->transform(v1, "B", ros::Time(2.0),
54  "B", ros::Duration(3.0));
55  EXPECT_NEAR(v_advanced.getOrigin().getX(), -9, EPS);
56  EXPECT_NEAR(v_advanced.getOrigin().getY(), 18, EPS);
57  EXPECT_NEAR(v_advanced.getOrigin().getZ(), 27, EPS);
58 }
59 
60 
61 
62 TEST(TfBullet, Vector)
63 {
64  tf2::Stamped<btVector3> v1(btVector3(1,2,3), ros::Time(2.0), "A");
65 
66  // simple api
67  btVector3 v_simple = tf_buffer->transform(v1, "B", ros::Duration(2.0));
68  EXPECT_NEAR(v_simple.getX(), -9, EPS);
69  EXPECT_NEAR(v_simple.getY(), 18, EPS);
70  EXPECT_NEAR(v_simple.getZ(), 27, EPS);
71 
72  // advanced api
73  btVector3 v_advanced = tf_buffer->transform(v1, "B", ros::Time(2.0),
74  "B", ros::Duration(3.0));
75  EXPECT_NEAR(v_advanced.getX(), -9, EPS);
76  EXPECT_NEAR(v_advanced.getY(), 18, EPS);
77  EXPECT_NEAR(v_advanced.getZ(), 27, EPS);
78 }
79 
80 
81 
82 
83 int main(int argc, char **argv){
84  testing::InitGoogleTest(&argc, argv);
85  ros::init(argc, argv, "test");
87 
88  tf_buffer = new tf2_ros::Buffer();
89 
90  // populate buffer
91  geometry_msgs::TransformStamped t;
92  t.transform.translation.x = 10;
93  t.transform.translation.y = 20;
94  t.transform.translation.z = 30;
95  t.transform.rotation.x = 1;
96  t.header.stamp = ros::Time(2.0);
97  t.header.frame_id = "A";
98  t.child_frame_id = "B";
99  tf_buffer->setTransform(t, "test");
100 
101  int ret = RUN_ALL_TESTS();
102  delete tf_buffer;
103  return ret;
104 }
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)
geometry_msgs::TransformStamped t
static const double EPS
tf2_ros::Buffer * tf_buffer
T & transform(const T &in, T &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
TEST(TfBullet, Transform)


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