Skip to content

Commit 88fe7de

Browse files
committed
Add more conversion tests
Tests for wrench conversion, Eigen <-> KDL and the error messaging facilities from convert.h
1 parent 917ccc6 commit 88fe7de

File tree

1 file changed

+156
-3
lines changed

1 file changed

+156
-3
lines changed

test_tf2/test/test_convert.cpp

Lines changed: 156 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -34,16 +34,70 @@
3434
*
3535
* Author: Eitan Marder-Eppstein
3636
*********************************************************************/
37+
38+
#include <geometry_msgs/msg/vector3_stamped.hpp>
3739
#include <gtest/gtest.h>
3840
#include <geometry_msgs/msg/point_stamped.hpp>
3941
#include <geometry_msgs/msg/point.hpp>
4042
#include <geometry_msgs/msg/vector3.hpp>
4143
#include <tf2/convert.h>
4244
#include <tf2/LinearMath/Quaternion.h>
43-
#include <tf2_kdl/tf2_kdl.hpp>
4445
#include <tf2_bullet/tf2_bullet.hpp>
4546
#include <tf2_eigen/tf2_eigen.hpp>
4647
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
48+
#include <tf2_kdl/tf2_kdl.hpp>
49+
50+
51+
// test of tf2 type traits
52+
static_assert(
53+
!tf2::impl::MessageHasStdHeader<geometry_msgs::msg::Vector3>::value,
54+
"MessageHasStdHeader traits error");
55+
static_assert(
56+
tf2::impl::MessageHasStdHeader<geometry_msgs::msg::Vector3Stamped>::value,
57+
"MessageHasStdHeader traits error");
58+
59+
namespace
60+
{
61+
struct MyPODMessage
62+
{
63+
int header;
64+
};
65+
66+
template<typename Alloc>
67+
struct MyAllocMessage
68+
{
69+
int header;
70+
};
71+
72+
static_assert(
73+
!tf2::impl::MessageHasStdHeader<MyPODMessage>::value,
74+
"MessageHasStdHeader traits error");
75+
76+
template<typename T>
77+
struct MyAllocator
78+
{
79+
using value_type = T;
80+
using size_type = unsigned int;
81+
T * allocate(size_type);
82+
void deallocate(T *, size_type);
83+
template<class U>
84+
struct rebind { typedef MyAllocator<U> other; };
85+
};
86+
using MyVec = geometry_msgs::msg::Vector3_<MyAllocator<void>>;
87+
using MyVecStamped = geometry_msgs::msg::Vector3Stamped_<MyAllocator<void>>;
88+
using MyMessage = MyAllocMessage<MyAllocator<void>>;
89+
90+
static_assert(!tf2::impl::MessageHasStdHeader<MyVec>::value, "MessageHasStdHeader traits error");
91+
static_assert(
92+
tf2::impl::MessageHasStdHeader<MyVecStamped>::value,
93+
"MessageHasStdHeader traits error");
94+
95+
static_assert(
96+
!tf2::impl::MessageHasStdHeader<MyMessage>::value,
97+
"MessageHasStdHeader traits error");
98+
} // namespace
99+
100+
using Vector6d = Eigen::Matrix<double, 6, 1>;
47101

48102
#include <Eigen/Geometry>
49103

@@ -108,8 +162,7 @@ TEST(tf2Convert, ConvertTf2Quaternion)
108162
{
109163
const tf2::Quaternion tq(1, 2, 3, 4);
110164
Eigen::Quaterniond eq;
111-
// TODO(gleichdick): switch to tf2::convert() when it's working
112-
tf2::fromMsg(tf2::toMsg(tq), eq);
165+
tf2::convert(tq, eq);
113166

114167
EXPECT_EQ(tq.w(), eq.w());
115168
EXPECT_EQ(tq.x(), eq.x());
@@ -188,6 +241,106 @@ TEST(tf2Convert, PointVectorOtherMessagetype)
188241
}
189242
}
190243

244+
TEST(TfEigenKdl, TestRotationQuaternion)
245+
{
246+
const auto kdl_v = KDL::Rotation::RPY(1.5, 0.2, 0.3);
247+
Eigen::Quaterniond eigen_v = Eigen::Quaterniond::Identity();
248+
tf2::convert(kdl_v, eigen_v);
249+
KDL::Rotation kdl_v1;
250+
tf2::convert(eigen_v, kdl_v1);
251+
EXPECT_EQ(kdl_v, kdl_v1);
252+
}
253+
254+
TEST(TfEigenKdl, TestQuaternionRotation)
255+
{
256+
const Eigen::Quaterniond eigen_v = Eigen::Quaterniond(1, 2, 1.5, 3).normalized();
257+
KDL::Rotation kdl_v;
258+
tf2::convert(eigen_v, kdl_v);
259+
Eigen::Quaterniond eigen_v1;
260+
tf2::convert(kdl_v, eigen_v1);
261+
EXPECT_TRUE(eigen_v.isApprox(eigen_v1));
262+
}
263+
264+
TEST(TfEigenKdl, TestFrameIsometry3d)
265+
{
266+
const auto kdl_v = KDL::Frame(KDL::Rotation::RPY(1.2, 0.2, 0), KDL::Vector(1, 2, 3));
267+
Eigen::Isometry3d eigen_v = Eigen::Isometry3d::Identity();
268+
tf2::convert(kdl_v, eigen_v);
269+
KDL::Frame kdl_v1;
270+
tf2::convert(eigen_v, kdl_v1);
271+
EXPECT_EQ(kdl_v, kdl_v1);
272+
}
273+
274+
TEST(TfEigenKdl, TestIsometry3dFrame)
275+
{
276+
const Eigen::Isometry3d eigen_v(
277+
Eigen::Translation3d(1, 2, 3) * Eigen::AngleAxisd(1, Eigen::Vector3d::UnitX()));
278+
KDL::Frame kdl_v;
279+
tf2::convert(eigen_v, kdl_v);
280+
Eigen::Isometry3d eigen_v1;
281+
tf2::convert(kdl_v, eigen_v1);
282+
EXPECT_EQ(eigen_v.translation(), eigen_v1.translation());
283+
EXPECT_EQ(eigen_v.rotation(), eigen_v1.rotation());
284+
}
285+
286+
TEST(TfEigenKdl, TestFrameAffine3d)
287+
{
288+
const auto kdl_v = KDL::Frame(KDL::Rotation::RPY(1.2, 0.2, 0), KDL::Vector(1, 2, 3));
289+
Eigen::Affine3d eigen_v = Eigen::Affine3d::Identity();
290+
tf2::convert(kdl_v, eigen_v);
291+
KDL::Frame kdl_v1;
292+
tf2::convert(eigen_v, kdl_v1);
293+
EXPECT_EQ(kdl_v, kdl_v1);
294+
}
295+
296+
TEST(TfEigenKdl, TestTwistMatrix)
297+
{
298+
const auto kdl_v = KDL::Twist(KDL::Vector(1, 2, 3), KDL::Vector(4, 5, 6));
299+
Vector6d eigen_v;
300+
tf2::convert(kdl_v, eigen_v);
301+
KDL::Twist kdl_v1;
302+
tf2::convert(eigen_v, kdl_v1);
303+
EXPECT_EQ(kdl_v, kdl_v1);
304+
}
305+
306+
TEST(TfEigenKdl, TestMatrixWrench)
307+
{
308+
Vector6d eigen_v;
309+
eigen_v << 1, 2, 3, 3, 2, 1;
310+
KDL::Wrench kdl_v;
311+
tf2::convert(eigen_v, kdl_v);
312+
std::array<tf2::Vector3, 2> tf2_v;
313+
tf2::convert(kdl_v, tf2_v);
314+
Vector6d eigen_v1;
315+
tf2::convert(tf2_v, eigen_v1);
316+
std::array<tf2::Vector3, 2> tf2_v1;
317+
tf2::convert(eigen_v1, tf2_v1);
318+
Vector6d eigen_v2;
319+
tf2::convert(tf2_v1, eigen_v2);
320+
EXPECT_EQ(eigen_v, eigen_v2);
321+
}
322+
323+
TEST(TfEigenKdl, TestVectorVector3d)
324+
{
325+
const auto kdl_v = KDL::Vector(1, 2, 3);
326+
Eigen::Vector3d eigen_v;
327+
tf2::convert(kdl_v, eigen_v);
328+
KDL::Vector kdl_v1;
329+
tf2::convert(eigen_v, kdl_v1);
330+
EXPECT_EQ(kdl_v, kdl_v1);
331+
}
332+
333+
TEST(TfEigenKdl, TestVector3dVector)
334+
{
335+
Eigen::Vector3d eigen_v;
336+
eigen_v << 1, 2, 3;
337+
KDL::Vector kdl_v;
338+
tf2::convert(eigen_v, kdl_v);
339+
Eigen::Vector3d eigen_v1;
340+
tf2::convert(kdl_v, eigen_v1);
341+
EXPECT_EQ(eigen_v, eigen_v1);
342+
}
343+
191344
int main(int argc, char ** argv)
192345
{
193346
testing::InitGoogleTest(&argc, argv);

0 commit comments

Comments
 (0)