This repository was archived by the owner on May 31, 2025. It is now read-only.
File tree Expand file tree Collapse file tree 4 files changed +28
-1
lines changed Expand file tree Collapse file tree 4 files changed +28
-1
lines changed Original file line number Diff line number Diff line change @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 2.8.3)
22
33project (test_tf2)
44
5- find_package (catkin REQUIRED COMPONENTS rosconsole roscpp rostest tf tf2 tf2_bullet tf2_ros tf2_geometry_msgs tf2_kdl tf2_msgs)
5+ find_package (catkin REQUIRED COMPONENTS rosconsole roscpp rostest tf tf2 tf2_bullet tf2_ros tf2_geometry_msgs tf2_kdl tf2_msgs tf2_eigen )
66find_package (Boost REQUIRED COMPONENTS thread)
77find_package (orocos_kdl REQUIRED)
88
Original file line number Diff line number Diff line change 2323 <build_depend >tf2_geometry_msgs</build_depend >
2424 <build_depend >tf2_kdl</build_depend >
2525 <build_depend >tf2_msgs</build_depend >
26+ <build_depend >tf2_eigen</build_depend >
2627
2728 <run_depend >rosconsole</run_depend >
2829 <run_depend >roscpp</run_depend >
3435 <run_depend >tf2_geometry_msgs</run_depend >
3536 <run_depend >tf2_kdl</run_depend >
3637 <run_depend >tf2_msgs</run_depend >
38+ <run_depend >tf2_eigen</run_depend >
3739
3840 <test_depend >rosunit</test_depend >
3941 <test_depend >rosbash</test_depend >
Original file line number Diff line number Diff line change 3939#include < tf2_kdl/tf2_kdl.h>
4040#include < tf2_bullet/tf2_bullet.h>
4141#include < tf2_geometry_msgs/tf2_geometry_msgs.h>
42+ #include < tf2_eigen/tf2_eigen.h>
4243#include < ros/time.h>
4344
4445TEST (tf2Convert, kdlToBullet)
@@ -97,6 +98,18 @@ TEST(tf2Convert, kdlBulletROSConversions)
9798 EXPECT_NEAR (b1.z (), b4.z (), epsilon);
9899}
99100
101+ TEST (tf2Convert, ConvertTf2Quaternion)
102+ {
103+ tf2::Quaternion tq (1 ,2 ,3 ,4 );
104+ Eigen::Quaterniond eq;
105+ tf2::convert (tq, eq);
106+
107+ EXPECT_EQ (tq.w (), eq.w ());
108+ EXPECT_EQ (tq.x (), eq.x ());
109+ EXPECT_EQ (tq.y (), eq.y ());
110+ EXPECT_EQ (tq.z (), eq.z ());
111+ }
112+
100113int main (int argc, char ** argv)
101114{
102115 testing::InitGoogleTest (&argc, argv);
Original file line number Diff line number Diff line change @@ -55,21 +55,33 @@ template <>
5555template <typename A, typename B>
5656inline void Converter<true , false >::convert(const A& a, B& b)
5757{
58+ #ifdef _MSC_VER
59+ tf2::fromMsg (a, b);
60+ #else
5861 fromMsg (a, b);
62+ #endif
5963}
6064
6165template <>
6266template <typename A, typename B>
6367inline void Converter<false , true >::convert(const A& a, B& b)
6468{
69+ #ifdef _MSC_VER
70+ b = tf2::toMsg (a);
71+ #else
6572 b = toMsg (a);
73+ #endif
6674}
6775
6876template <>
6977template <typename A, typename B>
7078inline void Converter<false , false >::convert(const A& a, B& b)
7179{
80+ #ifdef _MSC_VER
81+ tf2::fromMsg (tf2::toMsg (a), b);
82+ #else
7283 fromMsg (toMsg (a), b);
84+ #endif
7385}
7486
7587}
You can’t perform that action at this time.
0 commit comments