test_tf2_kdl.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_kdl/tf2_kdl.h>
34 #include <kdl/frames_io.hpp>
35 #include <gtest/gtest.h>
36 #include "tf2_ros/buffer.h"
37 
38 
40 static const double EPS = 1e-3;
41 
42 TEST(TfKDL, Frame)
43 {
45 
46 
47  // simple api
48  KDL::Frame v_simple = tf_buffer->transform(v1, "B", ros::Duration(2.0));
49  EXPECT_NEAR(v_simple.p[0], -9, EPS);
50  EXPECT_NEAR(v_simple.p[1], 18, EPS);
51  EXPECT_NEAR(v_simple.p[2], 27, EPS);
52  double r, p, y;
53  v_simple.M.GetRPY(r, p, y);
54  EXPECT_NEAR(r, 0.0, EPS);
55  EXPECT_NEAR(p, 0.0, EPS);
56  EXPECT_NEAR(y, 0.0, EPS);
57 
58 
59  // advanced api
60  KDL::Frame v_advanced = tf_buffer->transform(v1, "B", ros::Time(2.0),
61  "A", ros::Duration(3.0));
62  EXPECT_NEAR(v_advanced.p[0], -9, EPS);
63  EXPECT_NEAR(v_advanced.p[1], 18, EPS);
64  EXPECT_NEAR(v_advanced.p[2], 27, EPS);
65  v_advanced.M.GetRPY(r, p, y);
66  EXPECT_NEAR(r, 0.0, EPS);
67  EXPECT_NEAR(p, 0.0, EPS);
68  EXPECT_NEAR(y, 0.0, EPS);
69 
70 }
71 
72 
73 
74 TEST(TfKDL, Vector)
75 {
76  tf2::Stamped<KDL::Vector> v1(KDL::Vector(1,2,3), ros::Time(2.0), "A");
77 
78 
79  // simple api
80  KDL::Vector v_simple = tf_buffer->transform(v1, "B", ros::Duration(2.0));
81  EXPECT_NEAR(v_simple[0], -9, EPS);
82  EXPECT_NEAR(v_simple[1], 18, EPS);
83  EXPECT_NEAR(v_simple[2], 27, EPS);
84 
85  // advanced api
86  KDL::Vector v_advanced = tf_buffer->transform(v1, "B", ros::Time(2.0),
87  "A", ros::Duration(3.0));
88  EXPECT_NEAR(v_advanced[0], -9, EPS);
89  EXPECT_NEAR(v_advanced[1], 18, EPS);
90  EXPECT_NEAR(v_advanced[2], 27, EPS);
91 }
92 
93 TEST(TfKDL, ConvertVector)
94 {
95  tf2::Stamped<KDL::Vector> v(KDL::Vector(1,2,3), ros::Time(), "my_frame");
96 
98  tf2::convert(v1, v1);
99 
100  EXPECT_EQ(v, v1);
101 
102  tf2::Stamped<KDL::Vector> v2(KDL::Vector(3,4,5), ros::Time(), "my_frame2");
103  tf2::convert(v1, v2);
104 
105  EXPECT_EQ(v, v2);
106  EXPECT_EQ(v1, v2);
107 }
108 
109 
110 int main(int argc, char **argv){
111  testing::InitGoogleTest(&argc, argv);
112  ros::init(argc, argv, "test");
113  ros::NodeHandle n;
114 
115  tf_buffer = new tf2_ros::Buffer();
116 
117  // populate buffer
118  geometry_msgs::TransformStamped t;
119  t.transform.translation.x = 10;
120  t.transform.translation.y = 20;
121  t.transform.translation.z = 30;
122  t.transform.rotation.x = 1;
123  t.header.stamp = ros::Time(2.0);
124  t.header.frame_id = "A";
125  t.child_frame_id = "B";
126  tf_buffer->setTransform(t, "test");
127 
128  int retval = RUN_ALL_TESTS();
129  delete tf_buffer;
130  return retval;
131 }
T & transform(const T &in, T &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
void GetRPY(double &roll, double &pitch, double &yaw) const
bool setTransform(const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false)
static const double EPS
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Rotation M
static Rotation RPY(double roll, double pitch, double yaw)
int main(int argc, char **argv)
TEST(TfKDL, Frame)
void convert(const A &a, B &b)
tf2_ros::Buffer * tf_buffer


tf2_kdl
Author(s): Wim Meeussen
autogenerated on Mon Jun 27 2022 02:43:23