3838#include < tf2/convert.h>
3939#include < tf2_kdl/tf2_kdl.hpp>
4040#include < tf2_bullet/tf2_bullet.hpp>
41+ #include < tf2_eigen/tf2_eigen.hpp>
4142#include < tf2_geometry_msgs/tf2_geometry_msgs.hpp>
4243
4344TEST (tf2Convert, kdlToBullet)
4445{
4546 double epsilon = 1e-9 ;
4647
47- tf2::Stamped<btVector3> b (btVector3 (1 ,2 , 3 ), tf2::timeFromSec (0 ), " my_frame" );
48+ tf2::Stamped<btVector3> b (btVector3 (1 , 2 , 3 ), tf2::timeFromSec (0 ), " my_frame" );
4849
4950 tf2::Stamped<btVector3> b1 = b;
5051 tf2::Stamped<KDL::Vector> k1;
@@ -71,7 +72,7 @@ TEST(tf2Convert, kdlBulletROSConversions)
7172{
7273 double epsilon = 1e-9 ;
7374
74- tf2::Stamped<btVector3> b1 (btVector3 (1 ,2 , 3 ), tf2::timeFromSec (0 ), " my_frame" ), b2, b3, b4;
75+ tf2::Stamped<btVector3> b1 (btVector3 (1 , 2 , 3 ), tf2::timeFromSec (0 ), " my_frame" ), b2, b3, b4;
7576 geometry_msgs::msg::PointStamped r1, r2, r3;
7677 tf2::Stamped<KDL::Vector> k1, k2, k3;
7778
@@ -96,7 +97,91 @@ TEST(tf2Convert, kdlBulletROSConversions)
9697 EXPECT_NEAR (b1.z (), b4.z (), epsilon);
9798}
9899
99- int main (int argc, char ** argv)
100+ TEST (tf2Convert, ConvertTf2Quaternion)
101+ {
102+ const tf2::Quaternion tq (1 , 2 , 3 , 4 );
103+ Eigen::Quaterniond eq;
104+ // tf2::convert(tq, eq);
105+ tf2::fromMsg (tf2::toMsg (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+
113+ TEST (tf2Convert, PointVectorDefaultMessagetype)
114+ {
115+ // Verify the return type of `toMsg()`
116+ // as it can return a Vector3 or a Point for certain datatypes
117+ {
118+ // Bullet
119+ const tf2::Stamped<btVector3> b1{btVector3{1.0 , 3.0 , 4.0 }, tf2::TimePoint (), " my_frame" };
120+ const geometry_msgs::msg::PointStamped msg = tf2::toMsg (b1);
121+
122+ EXPECT_EQ (msg.point .x , 1.0 );
123+ EXPECT_EQ (msg.point .y , 3.0 );
124+ EXPECT_EQ (msg.point .z , 4.0 );
125+ EXPECT_EQ (msg.header .frame_id , b1.frame_id_ );
126+ }
127+ {
128+ // Eigen
129+ const Eigen::Vector3d e1 {2.0 , 4.0 , 5.0 };
130+ const geometry_msgs::msg::Point msg = tf2::toMsg (e1 );
131+
132+ EXPECT_EQ (msg.x , 2.0 );
133+ EXPECT_EQ (msg.y , 4.0 );
134+ EXPECT_EQ (msg.z , 5.0 );
135+ }
136+ {
137+ // tf2
138+ const tf2::Vector3 t1{2.0 , 4.0 , 5.0 };
139+ const geometry_msgs::msg::Vector3 msg = tf2::toMsg (t1);
140+
141+ EXPECT_EQ (msg.x , 2.0 );
142+ EXPECT_EQ (msg.y , 4.0 );
143+ EXPECT_EQ (msg.z , 5.0 );
144+ }
145+ {
146+ // KDL
147+ const tf2::Stamped<KDL::Vector> k1{KDL::Vector{1.0 , 3.0 , 4.0 }, tf2::TimePoint (), " my_frame" };
148+ const geometry_msgs::msg::PointStamped msg = tf2::toMsg (k1);
149+
150+ EXPECT_EQ (msg.point .x , 1.0 );
151+ EXPECT_EQ (msg.point .y , 3.0 );
152+ EXPECT_EQ (msg.point .z , 4.0 );
153+ EXPECT_EQ (msg.header .frame_id , k1.frame_id_ );
154+ }
155+ }
156+
157+ TEST (tf2Convert, PointVectorOtherMessagetype)
158+ {
159+ {
160+ const tf2::Vector3 t1{2.0 , 4.0 , 5.0 };
161+ geometry_msgs::msg::Point msg;
162+ const geometry_msgs::msg::Point & msg2 = tf2::toMsg (t1, msg);
163+
164+ // returned reference is second argument
165+ EXPECT_EQ (&msg2, &msg);
166+ EXPECT_EQ (msg.x , 2.0 );
167+ EXPECT_EQ (msg.y , 4.0 );
168+ EXPECT_EQ (msg.z , 5.0 );
169+ }
170+ {
171+ // Eigen
172+ const Eigen::Vector3d e1 {2.0 , 4.0 , 5.0 };
173+ geometry_msgs::msg::Vector3 msg;
174+ const geometry_msgs::msg::Vector3 & msg2 = tf2::toMsg (e1 , msg);
175+
176+ // returned reference is second argument
177+ EXPECT_EQ (&msg2, &msg);
178+ EXPECT_EQ (msg.x , 2.0 );
179+ EXPECT_EQ (msg.y , 4.0 );
180+ EXPECT_EQ (msg.z , 5.0 );
181+ }
182+ }
183+
184+ int main (int argc, char ** argv)
100185{
101186 testing::InitGoogleTest (&argc, argv);
102187 return RUN_ALL_TESTS ();
0 commit comments