$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00033 #include <tf2_kdl/tf2_kdl.h> 00034 #include <ros/ros.h> 00035 #include <kdl/frames_io.hpp> 00036 #include <gtest/gtest.h> 00037 00038 00039 tf2::Buffer* tf_buffer; 00040 static const double EPS = 1e-3; 00041 00042 TEST(TfKDL, Frame) 00043 { 00044 tf2::Stamped<KDL::Frame> v1(KDL::Frame(KDL::Rotation::RPY(M_PI, 0, 0), KDL::Vector(1,2,3)), ros::Time(2.0), "A"); 00045 00046 00047 // simple api 00048 KDL::Frame v_simple = tf_buffer->transform(v1, "B", ros::Duration(2.0)); 00049 EXPECT_NEAR(v_simple.p[0], -9, EPS); 00050 EXPECT_NEAR(v_simple.p[1], 18, EPS); 00051 EXPECT_NEAR(v_simple.p[2], 27, EPS); 00052 double r, p, y; 00053 v_simple.M.GetRPY(r, p, y); 00054 EXPECT_NEAR(r, 0.0, EPS); 00055 EXPECT_NEAR(p, 0.0, EPS); 00056 EXPECT_NEAR(y, 0.0, EPS); 00057 00058 00059 // advanced api 00060 KDL::Frame v_advanced = tf_buffer->transform(v1, "B", ros::Time(2.0), 00061 "A", ros::Duration(3.0)); 00062 EXPECT_NEAR(v_advanced.p[0], -9, EPS); 00063 EXPECT_NEAR(v_advanced.p[1], 18, EPS); 00064 EXPECT_NEAR(v_advanced.p[2], 27, EPS); 00065 v_advanced.M.GetRPY(r, p, y); 00066 EXPECT_NEAR(r, 0.0, EPS); 00067 EXPECT_NEAR(p, 0.0, EPS); 00068 EXPECT_NEAR(y, 0.0, EPS); 00069 00070 } 00071 00072 00073 00074 TEST(TfKDL, Vector) 00075 { 00076 tf2::Stamped<KDL::Vector> v1(KDL::Vector(1,2,3), ros::Time(2.0), "A"); 00077 00078 00079 // simple api 00080 KDL::Vector v_simple = tf_buffer->transform(v1, "B", ros::Duration(2.0)); 00081 EXPECT_NEAR(v_simple[0], -9, EPS); 00082 EXPECT_NEAR(v_simple[1], 18, EPS); 00083 EXPECT_NEAR(v_simple[2], 27, EPS); 00084 00085 // advanced api 00086 KDL::Vector v_advanced = tf_buffer->transform(v1, "B", ros::Time(2.0), 00087 "A", ros::Duration(3.0)); 00088 EXPECT_NEAR(v_advanced[0], -9, EPS); 00089 EXPECT_NEAR(v_advanced[1], 18, EPS); 00090 EXPECT_NEAR(v_advanced[2], 27, EPS); 00091 } 00092 00093 TEST(TfKDL, ConvertVector) 00094 { 00095 tf2::Stamped<KDL::Vector> v(KDL::Vector(1,2,3), ros::Time(), "my_frame"); 00096 00097 tf2::Stamped<KDL::Vector> v1 = v; 00098 tf2::convert(v1, v1); 00099 00100 EXPECT_EQ(v, v1); 00101 00102 tf2::Stamped<KDL::Vector> v2(KDL::Vector(3,4,5), ros::Time(), "my_frame2"); 00103 tf2::convert(v1, v2); 00104 00105 EXPECT_EQ(v, v2); 00106 EXPECT_EQ(v1, v2); 00107 } 00108 00109 00110 int main(int argc, char **argv){ 00111 testing::InitGoogleTest(&argc, argv); 00112 ros::init(argc, argv, "test"); 00113 ros::NodeHandle n; 00114 00115 tf_buffer = new tf2::Buffer(); 00116 00117 // populate buffer 00118 geometry_msgs::TransformStamped t; 00119 t.transform.translation.x = 10; 00120 t.transform.translation.y = 20; 00121 t.transform.translation.z = 30; 00122 t.transform.rotation.x = 1; 00123 t.header.stamp = ros::Time(2.0); 00124 t.header.frame_id = "A"; 00125 t.child_frame_id = "B"; 00126 tf_buffer->setTransform(t, "test"); 00127 00128 bool retval = RUN_ALL_TESTS(); 00129 delete tf_buffer; 00130 return retval; 00131 }