tf2_eigen-test.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) Koji Terada
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  *
00014  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00015  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00016  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00017  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00018  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00019  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00020  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00021  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00022  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00023  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00024  * POSSIBILITY OF SUCH DAMAGE.
00025  */
00026 
00030 #include <tf2_eigen/tf2_eigen.h>
00031 #include <ros/ros.h>
00032 #include <gtest/gtest.h>
00033 #include <tf2/convert.h>
00034 
00035 TEST(TfEigen, ConvertVector3dStamped)
00036 {
00037   const tf2::Stamped<Eigen::Vector3d> v(Eigen::Vector3d(1,2,3), ros::Time(5), "test");
00038 
00039   tf2::Stamped<Eigen::Vector3d> v1;
00040   geometry_msgs::PointStamped p1;
00041   tf2::convert(v, p1);
00042   tf2::convert(p1, v1);
00043 
00044   EXPECT_EQ(v, v1);
00045 }
00046 
00047 TEST(TfEigen, ConvertVector3d)
00048 {
00049   const Eigen::Vector3d v(1,2,3);
00050 
00051   Eigen::Vector3d v1;
00052   geometry_msgs::Point p1;
00053   tf2::convert(v, p1);
00054   tf2::convert(p1, v1);
00055 
00056   EXPECT_EQ(v, v1);
00057 }
00058 
00059 TEST(TfEigen, ConvertQuaterniondStamped)
00060 {
00061   const tf2::Stamped<Eigen::Quaterniond> v(Eigen::Quaterniond(1,2,3,4), ros::Time(5), "test");
00062 
00063   tf2::Stamped<Eigen::Quaterniond> v1;
00064   geometry_msgs::QuaternionStamped p1;
00065   tf2::convert(v, p1);
00066   tf2::convert(p1, v1);
00067 
00068   EXPECT_EQ(v.frame_id_, v1.frame_id_);
00069   EXPECT_EQ(v.stamp_, v1.stamp_);
00070   EXPECT_EQ(v.w(), v1.w());
00071   EXPECT_EQ(v.x(), v1.x());
00072   EXPECT_EQ(v.y(), v1.y());
00073   EXPECT_EQ(v.z(), v1.z());
00074 }
00075 
00076 TEST(TfEigen, ConvertQuaterniond)
00077 {
00078   const Eigen::Quaterniond v(1,2,3,4);
00079 
00080   Eigen::Quaterniond v1;
00081   geometry_msgs::Quaternion p1;
00082   tf2::convert(v, p1);
00083   tf2::convert(p1, v1);
00084 
00085   EXPECT_EQ(v.w(), v1.w());
00086   EXPECT_EQ(v.x(), v1.x());
00087   EXPECT_EQ(v.y(), v1.y());
00088   EXPECT_EQ(v.z(), v1.z());
00089 }
00090 
00091 TEST(TfEigen, TransformQuaterion) {
00092  const tf2::Stamped<Eigen::Quaterniond> in(Eigen::Quaterniond(Eigen::AngleAxisd(1, Eigen::Vector3d::UnitX())), ros::Time(5), "test");
00093  const Eigen::Affine3d r(Eigen::AngleAxisd(M_PI/2, Eigen::Vector3d::UnitY()));
00094  const tf2::Stamped<Eigen::Quaterniond> expected(Eigen::Quaterniond(Eigen::AngleAxisd(1, Eigen::Vector3d::UnitZ())), ros::Time(10), "expected");
00095 
00096  geometry_msgs::TransformStamped trafo = tf2::eigenToTransform(r);
00097  trafo.header.stamp = ros::Time(10);
00098  trafo.header.frame_id = "expected";
00099 
00100  tf2::Stamped<Eigen::Quaterniond> out;
00101  tf2::doTransform(in, out, trafo);
00102 
00103  EXPECT_TRUE(out.isApprox(expected));
00104  EXPECT_EQ(expected.stamp_, out.stamp_);
00105  EXPECT_EQ(expected.frame_id_, out.frame_id_);
00106 }
00107 
00108 TEST(TfEigen, ConvertAffine3dStamped)
00109 {
00110   const Eigen::Affine3d v_nonstamped(Eigen::Translation3d(1,2,3) * Eigen::AngleAxis<double>(1, Eigen::Vector3d::UnitX()));
00111   const tf2::Stamped<Eigen::Affine3d> v(v_nonstamped, ros::Time(42), "test_frame");
00112 
00113   tf2::Stamped<Eigen::Affine3d> v1;
00114   geometry_msgs::PoseStamped p1;
00115   tf2::convert(v, p1);
00116   tf2::convert(p1, v1);
00117 
00118   EXPECT_EQ(v.translation(), v1.translation());
00119   EXPECT_EQ(v.rotation(), v1.rotation());
00120   EXPECT_EQ(v.frame_id_, v1.frame_id_);
00121   EXPECT_EQ(v.stamp_, v1.stamp_);
00122 }
00123 
00124 TEST(TfEigen, ConvertAffine3d)
00125 {
00126   const Eigen::Affine3d v(Eigen::Translation3d(1,2,3) * Eigen::AngleAxis<double>(1, Eigen::Vector3d::UnitX()));
00127 
00128   Eigen::Affine3d v1;
00129   geometry_msgs::Pose p1;
00130   tf2::convert(v, p1);
00131   tf2::convert(p1, v1);
00132 
00133   EXPECT_EQ(v.translation(), v1.translation());
00134   EXPECT_EQ(v.rotation(), v1.rotation());
00135 }
00136 
00137 TEST(TfEigen, ConvertTransform)
00138 {
00139   Eigen::Matrix4d tm;
00140 
00141   double alpha = M_PI/4.0;
00142   double theta = M_PI/6.0;
00143   double gamma = M_PI/12.0;
00144 
00145   tm << cos(theta)*cos(gamma),-cos(theta)*sin(gamma),sin(theta), 1, //
00146   cos(alpha)*sin(gamma)+sin(alpha)*sin(theta)*cos(gamma),cos(alpha)*cos(gamma)-sin(alpha)*sin(theta)*sin(gamma),-sin(alpha)*cos(theta), 2, //
00147   sin(alpha)*sin(gamma)-cos(alpha)*sin(theta)*cos(gamma),cos(alpha)*sin(theta)*sin(gamma)+sin(alpha)*cos(gamma),cos(alpha)*cos(theta), 3, //
00148   0, 0, 0, 1;
00149 
00150   Eigen::Affine3d T(tm);
00151 
00152   geometry_msgs::TransformStamped msg = tf2::eigenToTransform(T);
00153   Eigen::Affine3d Tback = tf2::transformToEigen(msg);
00154 
00155   EXPECT_TRUE(T.isApprox(Tback));
00156   EXPECT_TRUE(tm.isApprox(Tback.matrix()));
00157 
00158 }
00159 
00160 
00161 
00162 int main(int argc, char **argv){
00163   testing::InitGoogleTest(&argc, argv);
00164 
00165   return RUN_ALL_TESTS();
00166 }


tf2_eigen
Author(s): Koji Terada
autogenerated on Mon Oct 2 2017 02:24:39