3434*
3535* Author: Eitan Marder-Eppstein
3636*********************************************************************/
37+
38+ #include < geometry_msgs/msg/vector3_stamped.hpp>
3739#include < gtest/gtest.h>
3840#include < tf2/convert.h>
39- #include < tf2_kdl/tf2_kdl.hpp>
40- #include < tf2_bullet/tf2_bullet.hpp>
4141#include < tf2_eigen/tf2_eigen.hpp>
42+ #include < tf2_bullet/tf2_bullet.hpp>
4243#include < tf2_geometry_msgs/tf2_geometry_msgs.hpp>
44+ #include < tf2_kdl/tf2_kdl.hpp>
45+
46+
47+ // test of tf2 type traits
48+ static_assert (
49+ !tf2::impl::MessageHasStdHeader<geometry_msgs::msg::Vector3>::value,
50+ " MessageHasStdHeader traits error" );
51+ static_assert (
52+ tf2::impl::MessageHasStdHeader<geometry_msgs::msg::Vector3Stamped>::value,
53+ " MessageHasStdHeader traits error" );
54+
55+ namespace
56+ {
57+ struct MyPODMessage
58+ {
59+ int header;
60+ };
61+
62+ template <typename Alloc>
63+ struct MyAllocMessage
64+ {
65+ int header;
66+ };
67+
68+ static_assert (
69+ !tf2::impl::MessageHasStdHeader<MyPODMessage>::value,
70+ " MessageHasStdHeader traits error" );
71+
72+ template <typename T>
73+ struct MyAllocator
74+ {
75+ using value_type = T;
76+ using size_type = unsigned int ;
77+ T * allocate (size_type);
78+ void deallocate (T *, size_type);
79+ template <class U >
80+ struct rebind { typedef MyAllocator<U> other; };
81+ };
82+ using MyVec = geometry_msgs::msg::Vector3_<MyAllocator<void >>;
83+ using MyVecStamped = geometry_msgs::msg::Vector3Stamped_<MyAllocator<void >>;
84+ using MyMessage = MyAllocMessage<MyAllocator<void >>;
85+
86+ static_assert (!tf2::impl::MessageHasStdHeader<MyVec>::value, " MessageHasStdHeader traits error" );
87+ static_assert (
88+ tf2::impl::MessageHasStdHeader<MyVecStamped>::value,
89+ " MessageHasStdHeader traits error" );
90+
91+ static_assert (
92+ !tf2::impl::MessageHasStdHeader<MyMessage>::value,
93+ " MessageHasStdHeader traits error" );
94+ } // namespace
95+
96+ using Vector6d = Eigen::Matrix<double , 6 , 1 >;
4397
4498TEST (tf2Convert, kdlToBullet)
4599{
@@ -76,7 +130,8 @@ TEST(tf2Convert, kdlBulletROSConversions)
76130 geometry_msgs::msg::PointStamped r1, r2, r3;
77131 tf2::Stamped<KDL::Vector> k1, k2, k3;
78132
79- // Do bullet -> self -> bullet -> KDL -> self -> KDL -> ROS -> self -> ROS -> KDL -> bullet -> ROS -> bullet
133+ // Do bullet -> self -> bullet -> KDL -> self -> KDL -> ROS -> self
134+ // -> ROS -> KDL -> bullet -> ROS -> bullet
80135 tf2::convert (b1, b1);
81136 tf2::convert (b1, b2);
82137 tf2::convert (b2, k1);
@@ -101,8 +156,7 @@ TEST(tf2Convert, ConvertTf2Quaternion)
101156{
102157 const tf2::Quaternion tq (1 , 2 , 3 , 4 );
103158 Eigen::Quaterniond eq;
104- // tf2::convert(tq, eq);
105- tf2::fromMsg (tf2::toMsg (tq), eq);
159+ tf2::convert (tq, eq);
106160
107161 EXPECT_EQ (tq.w (), eq.w ());
108162 EXPECT_EQ (tq.x (), eq.x ());
@@ -181,6 +235,106 @@ TEST(tf2Convert, PointVectorOtherMessagetype)
181235 }
182236}
183237
238+ TEST (TfEigenKdl, TestRotationQuaternion)
239+ {
240+ const auto kdl_v = KDL::Rotation::RPY (1.5 , 0.2 , 0.3 );
241+ Eigen::Quaterniond eigen_v = Eigen::Quaterniond::Identity ();
242+ tf2::convert (kdl_v, eigen_v);
243+ KDL::Rotation kdl_v1;
244+ tf2::convert (eigen_v, kdl_v1);
245+ EXPECT_EQ (kdl_v, kdl_v1);
246+ }
247+
248+ TEST (TfEigenKdl, TestQuaternionRotation)
249+ {
250+ const Eigen::Quaterniond eigen_v = Eigen::Quaterniond (1 , 2 , 1.5 , 3 ).normalized ();
251+ KDL::Rotation kdl_v;
252+ tf2::convert (eigen_v, kdl_v);
253+ Eigen::Quaterniond eigen_v1;
254+ tf2::convert (kdl_v, eigen_v1);
255+ EXPECT_TRUE (eigen_v.isApprox (eigen_v1));
256+ }
257+
258+ TEST (TfEigenKdl, TestFrameIsometry3d)
259+ {
260+ const auto kdl_v = KDL::Frame (KDL::Rotation::RPY (1.2 , 0.2 , 0 ), KDL::Vector (1 , 2 , 3 ));
261+ Eigen::Isometry3d eigen_v = Eigen::Isometry3d::Identity ();
262+ tf2::convert (kdl_v, eigen_v);
263+ KDL::Frame kdl_v1;
264+ tf2::convert (eigen_v, kdl_v1);
265+ EXPECT_EQ (kdl_v, kdl_v1);
266+ }
267+
268+ TEST (TfEigenKdl, TestIsometry3dFrame)
269+ {
270+ const Eigen::Isometry3d eigen_v (
271+ Eigen::Translation3d (1 , 2 , 3 ) * Eigen::AngleAxisd (1 , Eigen::Vector3d::UnitX ()));
272+ KDL::Frame kdl_v;
273+ tf2::convert (eigen_v, kdl_v);
274+ Eigen::Isometry3d eigen_v1;
275+ tf2::convert (kdl_v, eigen_v1);
276+ EXPECT_EQ (eigen_v.translation (), eigen_v1.translation ());
277+ EXPECT_EQ (eigen_v.rotation (), eigen_v1.rotation ());
278+ }
279+
280+ TEST (TfEigenKdl, TestFrameAffine3d)
281+ {
282+ const auto kdl_v = KDL::Frame (KDL::Rotation::RPY (1.2 , 0.2 , 0 ), KDL::Vector (1 , 2 , 3 ));
283+ Eigen::Affine3d eigen_v = Eigen::Affine3d::Identity ();
284+ tf2::convert (kdl_v, eigen_v);
285+ KDL::Frame kdl_v1;
286+ tf2::convert (eigen_v, kdl_v1);
287+ EXPECT_EQ (kdl_v, kdl_v1);
288+ }
289+
290+ TEST (TfEigenKdl, TestTwistMatrix)
291+ {
292+ const auto kdl_v = KDL::Twist (KDL::Vector (1 , 2 , 3 ), KDL::Vector (4 , 5 , 6 ));
293+ Vector6d eigen_v;
294+ tf2::convert (kdl_v, eigen_v);
295+ KDL::Twist kdl_v1;
296+ tf2::convert (eigen_v, kdl_v1);
297+ EXPECT_EQ (kdl_v, kdl_v1);
298+ }
299+
300+ TEST (TfEigenKdl, TestMatrixWrench)
301+ {
302+ Vector6d eigen_v;
303+ eigen_v << 1 , 2 , 3 , 3 , 2 , 1 ;
304+ KDL::Wrench kdl_v;
305+ tf2::convert (eigen_v, kdl_v);
306+ std::array<tf2::Vector3, 2 > tf2_v;
307+ tf2::convert (kdl_v, tf2_v);
308+ Vector6d eigen_v1;
309+ tf2::convert (tf2_v, eigen_v1);
310+ std::array<tf2::Vector3, 2 > tf2_v1;
311+ tf2::convert (eigen_v1, tf2_v1);
312+ Vector6d eigen_v2;
313+ tf2::convert (tf2_v1, eigen_v2);
314+ EXPECT_EQ (eigen_v, eigen_v2);
315+ }
316+
317+ TEST (TfEigenKdl, TestVectorVector3d)
318+ {
319+ const auto kdl_v = KDL::Vector (1 , 2 , 3 );
320+ Eigen::Vector3d eigen_v;
321+ tf2::convert (kdl_v, eigen_v);
322+ KDL::Vector kdl_v1;
323+ tf2::convert (eigen_v, kdl_v1);
324+ EXPECT_EQ (kdl_v, kdl_v1);
325+ }
326+
327+ TEST (TfEigenKdl, TestVector3dVector)
328+ {
329+ Eigen::Vector3d eigen_v;
330+ eigen_v << 1 , 2 , 3 ;
331+ KDL::Vector kdl_v;
332+ tf2::convert (eigen_v, kdl_v);
333+ Eigen::Vector3d eigen_v1;
334+ tf2::convert (kdl_v, eigen_v1);
335+ EXPECT_EQ (eigen_v, eigen_v1);
336+ }
337+
184338int main (int argc, char ** argv)
185339{
186340 testing::InitGoogleTest (&argc, argv);
0 commit comments