3636*********************************************************************/
3737#include < gtest/gtest.h>
3838#include < tf2/convert.h>
39- #include < tf2_kdl/tf2_kdl.hpp>
40- #include < tf2_bullet/tf2_bullet.hpp>
4139#include < tf2_eigen/tf2_eigen.hpp>
40+ #include < tf2_bullet/tf2_bullet.hpp>
4241#include < tf2_geometry_msgs/tf2_geometry_msgs.hpp>
42+ #include < tf2_kdl/tf2_kdl.hpp>
4343
4444TEST (tf2Convert, kdlToBullet)
4545{
@@ -76,7 +76,8 @@ TEST(tf2Convert, kdlBulletROSConversions)
7676 geometry_msgs::msg::PointStamped r1, r2, r3;
7777 tf2::Stamped<KDL::Vector> k1, k2, k3;
7878
79- // Do bullet -> self -> bullet -> KDL -> self -> KDL -> ROS -> self -> ROS -> KDL -> bullet -> ROS -> bullet
79+ // Do bullet -> self -> bullet -> KDL -> self -> KDL -> ROS -> self
80+ // -> ROS -> KDL -> bullet -> ROS -> bullet
8081 tf2::convert (b1, b1);
8182 tf2::convert (b1, b2);
8283 tf2::convert (b2, k1);
@@ -101,8 +102,7 @@ TEST(tf2Convert, ConvertTf2Quaternion)
101102{
102103 const tf2::Quaternion tq (1 , 2 , 3 , 4 );
103104 Eigen::Quaterniond eq;
104- // tf2::convert(tq, eq);
105- tf2::fromMsg (tf2::toMsg (tq), eq);
105+ tf2::convert (tq, eq);
106106
107107 EXPECT_EQ (tq.w (), eq.w ());
108108 EXPECT_EQ (tq.x (), eq.x ());
@@ -181,6 +181,80 @@ TEST(tf2Convert, PointVectorOtherMessagetype)
181181 }
182182}
183183
184+ TEST (TfEigenKdl, TestRotationQuaternion)
185+ {
186+ const auto kdl_v = KDL::Rotation::RPY (1.5 , 0.2 , 0.3 );
187+ Eigen::Quaterniond eigen_v = Eigen::Quaterniond::Identity ();
188+ tf2::convert (kdl_v, eigen_v);
189+ KDL::Rotation kdl_v1;
190+ tf2::convert (eigen_v, kdl_v1);
191+ EXPECT_EQ (kdl_v, kdl_v1);
192+ }
193+
194+ TEST (TfEigenKdl, TestQuaternionRotation)
195+ {
196+ const Eigen::Quaterniond eigen_v = Eigen::Quaterniond (1 , 2 , 1.5 , 3 ).normalized ();
197+ KDL::Rotation kdl_v;
198+ tf2::convert (eigen_v, kdl_v);
199+ Eigen::Quaterniond eigen_v1;
200+ tf2::convert (kdl_v, eigen_v1);
201+ EXPECT_TRUE (eigen_v.isApprox (eigen_v1));
202+ }
203+
204+ TEST (TfEigenKdl, TestFrameIsometry3d)
205+ {
206+ const auto kdl_v = KDL::Frame (KDL::Rotation::RPY (1.2 , 0.2 , 0 ), KDL::Vector (1 , 2 , 3 ));
207+ Eigen::Isometry3d eigen_v = Eigen::Isometry3d::Identity ();
208+ tf2::convert (kdl_v, eigen_v);
209+ KDL::Frame kdl_v1;
210+ tf2::convert (eigen_v, kdl_v1);
211+ EXPECT_EQ (kdl_v, kdl_v1);
212+ }
213+
214+ TEST (TfEigenKdl, TestIsometry3dFrame)
215+ {
216+ const Eigen::Isometry3d eigen_v (
217+ Eigen::Translation3d (1 , 2 , 3 ) * Eigen::AngleAxisd (1 , Eigen::Vector3d::UnitX ()));
218+ KDL::Frame kdl_v;
219+ tf2::convert (eigen_v, kdl_v);
220+ Eigen::Isometry3d eigen_v1;
221+ tf2::convert (kdl_v, eigen_v1);
222+ EXPECT_EQ (eigen_v.translation (), eigen_v1.translation ());
223+ EXPECT_EQ (eigen_v.rotation (), eigen_v1.rotation ());
224+ }
225+
226+ TEST (TfEigenKdl, TestFrameAffine3d)
227+ {
228+ const auto kdl_v = KDL::Frame (KDL::Rotation::RPY (1.2 , 0.2 , 0 ), KDL::Vector (1 , 2 , 3 ));
229+ Eigen::Affine3d eigen_v = Eigen::Affine3d::Identity ();
230+ tf2::convert (kdl_v, eigen_v);
231+ KDL::Frame kdl_v1;
232+ tf2::convert (eigen_v, kdl_v1);
233+ EXPECT_EQ (kdl_v, kdl_v1);
234+ }
235+
236+
237+ TEST (TfEigenKdl, TestVectorVector3d)
238+ {
239+ const auto kdl_v = KDL::Vector (1 , 2 , 3 );
240+ Eigen::Vector3d eigen_v;
241+ tf2::convert (kdl_v, eigen_v);
242+ KDL::Vector kdl_v1;
243+ tf2::convert (eigen_v, kdl_v1);
244+ EXPECT_EQ (kdl_v, kdl_v1);
245+ }
246+
247+ TEST (TfEigenKdl, TestVector3dVector)
248+ {
249+ Eigen::Vector3d eigen_v;
250+ eigen_v << 1 , 2 , 3 ;
251+ KDL::Vector kdl_v;
252+ tf2::convert (eigen_v, kdl_v);
253+ Eigen::Vector3d eigen_v1;
254+ tf2::convert (kdl_v, eigen_v1);
255+ EXPECT_EQ (eigen_v, eigen_v1);
256+ }
257+
184258int main (int argc, char ** argv)
185259{
186260 testing::InitGoogleTest (&argc, argv);
0 commit comments