tf2_eigen-test.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) Koji Terada
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  *
14  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
15  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
16  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
17  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
18  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
19  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
20  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
21  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
22  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
23  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
24  * POSSIBILITY OF SUCH DAMAGE.
25  */
26 
30 #include <tf2_eigen/tf2_eigen.h>
31 #include <gtest/gtest.h>
32 #include <tf2/convert.h>
33 
34 TEST(TfEigen, ConvertVector3dStamped)
35 {
36  const tf2::Stamped<Eigen::Vector3d> v(Eigen::Vector3d(1,2,3), ros::Time(5), "test");
37 
39  geometry_msgs::PointStamped p1;
40  tf2::convert(v, p1);
41  tf2::convert(p1, v1);
42 
43  EXPECT_EQ(v, v1);
44 }
45 
46 TEST(TfEigen, ConvertVector3d)
47 {
48  const Eigen::Vector3d v(1,2,3);
49 
50  Eigen::Vector3d v1;
51  geometry_msgs::Point p1;
52  tf2::convert(v, p1);
53  tf2::convert(p1, v1);
54 
55  EXPECT_EQ(v, v1);
56 }
57 
58 TEST(TfEigen, ConvertQuaterniondStamped)
59 {
60  const tf2::Stamped<Eigen::Quaterniond> v(Eigen::Quaterniond(1,2,3,4), ros::Time(5), "test");
61 
63  geometry_msgs::QuaternionStamped p1;
64  tf2::convert(v, p1);
65  tf2::convert(p1, v1);
66 
67  EXPECT_EQ(v.frame_id_, v1.frame_id_);
68  EXPECT_EQ(v.stamp_, v1.stamp_);
69  EXPECT_EQ(v.w(), v1.w());
70  EXPECT_EQ(v.x(), v1.x());
71  EXPECT_EQ(v.y(), v1.y());
72  EXPECT_EQ(v.z(), v1.z());
73 }
74 
75 TEST(TfEigen, ConvertQuaterniond)
76 {
77  const Eigen::Quaterniond v(1,2,3,4);
78 
79  Eigen::Quaterniond v1;
80  geometry_msgs::Quaternion p1;
81  tf2::convert(v, p1);
82  tf2::convert(p1, v1);
83 
84  EXPECT_EQ(v.w(), v1.w());
85  EXPECT_EQ(v.x(), v1.x());
86  EXPECT_EQ(v.y(), v1.y());
87  EXPECT_EQ(v.z(), v1.z());
88 }
89 
90 TEST(TfEigen, TransformQuaterion) {
91  const tf2::Stamped<Eigen::Quaterniond> in(Eigen::Quaterniond(Eigen::AngleAxisd(1, Eigen::Vector3d::UnitX())), ros::Time(5), "test");
92  const Eigen::Isometry3d iso(Eigen::AngleAxisd(M_PI/2, Eigen::Vector3d::UnitY()));
93  const Eigen::Affine3d affine(iso);
94  const tf2::Stamped<Eigen::Quaterniond> expected(Eigen::Quaterniond(Eigen::AngleAxisd(1, Eigen::Vector3d::UnitZ())), ros::Time(10), "expected");
95 
96  geometry_msgs::TransformStamped trafo = tf2::eigenToTransform(affine);
97  trafo.header.stamp = ros::Time(10);
98  trafo.header.frame_id = "expected";
99 
101  tf2::doTransform(in, out, trafo);
102 
103  EXPECT_TRUE(out.isApprox(expected));
104  EXPECT_EQ(expected.stamp_, out.stamp_);
105  EXPECT_EQ(expected.frame_id_, out.frame_id_);
106 
107  // the same using Isometry
108  trafo = tf2::eigenToTransform(iso);
109  trafo.header.stamp = ros::Time(10);
110  trafo.header.frame_id = "expected";
111  tf2::doTransform(in, out, trafo);
112 
113  EXPECT_TRUE(out.isApprox(expected));
114  EXPECT_EQ(expected.stamp_, out.stamp_);
115  EXPECT_EQ(expected.frame_id_, out.frame_id_);
116 }
117 
118 TEST(TfEigen, ConvertAffine3dStamped)
119 {
120  const Eigen::Affine3d v_nonstamped(Eigen::Translation3d(1,2,3) * Eigen::AngleAxis<double>(1, Eigen::Vector3d::UnitX()));
121  const tf2::Stamped<Eigen::Affine3d> v(v_nonstamped, ros::Time(42), "test_frame");
122 
124  geometry_msgs::PoseStamped p1;
125  tf2::convert(v, p1);
126  tf2::convert(p1, v1);
127 
128  EXPECT_EQ(v.translation(), v1.translation());
129  EXPECT_EQ(v.rotation(), v1.rotation());
130  EXPECT_EQ(v.frame_id_, v1.frame_id_);
131  EXPECT_EQ(v.stamp_, v1.stamp_);
132 }
133 
134 TEST(TfEigen, ConvertIsometry3dStamped)
135 {
136  const Eigen::Isometry3d v_nonstamped(Eigen::Translation3d(1,2,3) * Eigen::AngleAxis<double>(1, Eigen::Vector3d::UnitX()));
137  const tf2::Stamped<Eigen::Isometry3d> v(v_nonstamped, ros::Time(42), "test_frame");
138 
140  geometry_msgs::PoseStamped p1;
141  tf2::convert(v, p1);
142  tf2::convert(p1, v1);
143 
144  EXPECT_EQ(v.translation(), v1.translation());
145  EXPECT_EQ(v.rotation(), v1.rotation());
146  EXPECT_EQ(v.frame_id_, v1.frame_id_);
147  EXPECT_EQ(v.stamp_, v1.stamp_);
148 }
149 
150 TEST(TfEigen, ConvertAffine3d)
151 {
152  const Eigen::Affine3d v(Eigen::Translation3d(1,2,3) * Eigen::AngleAxis<double>(1, Eigen::Vector3d::UnitX()));
153 
154  Eigen::Affine3d v1;
155  geometry_msgs::Pose p1;
156  tf2::convert(v, p1);
157  tf2::convert(p1, v1);
158 
159  EXPECT_EQ(v.translation(), v1.translation());
160  EXPECT_EQ(v.rotation(), v1.rotation());
161 }
162 
163 TEST(TfEigen, ConvertIsometry3d)
164 {
165  const Eigen::Isometry3d v(Eigen::Translation3d(1,2,3) * Eigen::AngleAxis<double>(1, Eigen::Vector3d::UnitX()));
166 
167  Eigen::Isometry3d v1;
168  geometry_msgs::Pose p1;
169  tf2::convert(v, p1);
170  tf2::convert(p1, v1);
171 
172  EXPECT_EQ(v.translation(), v1.translation());
173  EXPECT_EQ(v.rotation(), v1.rotation());
174 }
175 
176 TEST(TfEigen, ConvertTransform)
177 {
178  Eigen::Matrix4d tm;
179 
180  double alpha = M_PI/4.0;
181  double theta = M_PI/6.0;
182  double gamma = M_PI/12.0;
183 
184  tm << cos(theta)*cos(gamma),-cos(theta)*sin(gamma),sin(theta), 1, //
185  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, //
186  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, //
187  0, 0, 0, 1;
188 
189  Eigen::Affine3d T(tm);
190 
191  geometry_msgs::TransformStamped msg = tf2::eigenToTransform(T);
192  Eigen::Affine3d Tback = tf2::transformToEigen(msg);
193 
194  EXPECT_TRUE(T.isApprox(Tback));
195  EXPECT_TRUE(tm.isApprox(Tback.matrix()));
196 
197  // same for Isometry
198  Eigen::Isometry3d I(tm);
199 
200  msg = tf2::eigenToTransform(T);
201  Eigen::Isometry3d Iback = tf2::transformToEigen(msg);
202 
203  EXPECT_TRUE(I.isApprox(Iback));
204  EXPECT_TRUE(tm.isApprox(Iback.matrix()));
205 }
206 
207 
208 
209 int main(int argc, char **argv){
210  testing::InitGoogleTest(&argc, argv);
211 
212  return RUN_ALL_TESTS();
213 }
geometry_msgs::TransformStamped eigenToTransform(const Eigen::Affine3d &T)
Convert an Eigen Affine3d transform to the equivalent geometry_msgs message type. ...
Definition: tf2_eigen.h:67
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
TEST(TfEigen, ConvertVector3dStamped)
ros::Time stamp_
std::string frame_id_
void convert(const A &a, B &b)
int main(int argc, char **argv)
Eigen::Isometry3d transformToEigen(const geometry_msgs::Transform &t)
Convert a timestamped transform to the equivalent Eigen data type.
Definition: tf2_eigen.h:48


tf2_eigen
Author(s): Koji Terada
autogenerated on Mon Jun 27 2022 02:43:11