Skip to content

Commit ef93ac3

Browse files
committed
Add test for Vector/Point toMsg()
1 parent 1c531b9 commit ef93ac3

File tree

3 files changed

+105
-17
lines changed

3 files changed

+105
-17
lines changed

test_tf2/CMakeLists.txt

Lines changed: 15 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -24,18 +24,17 @@ find_package(geometry_msgs REQUIRED)
2424
find_package(launch_testing_ament_cmake REQUIRED)
2525
find_package(rclcpp REQUIRED)
2626
find_package(tf2 REQUIRED)
27-
# TODO (ahcorde): activate when tf2_bullet is merged
28-
# find_package(tf2_bullet REQUIRED)
27+
find_package(tf2_bullet REQUIRED)
28+
find_package(tf2_eigen REQUIRED)
2929
find_package(tf2_geometry_msgs REQUIRED)
3030
find_package(tf2_kdl REQUIRED)
3131
find_package(tf2_ros REQUIRED)
3232

3333
ament_find_gtest()
3434

35-
# TODO (ahcorde): activate when tf2_bullet is merged
36-
# find_package(PkgConfig REQUIRED)
37-
# pkg_check_modules(bullet REQUIRED bullet)
38-
# include_directories(include ${bullet_INCLUDE_DIRS})
35+
find_package(PkgConfig REQUIRED)
36+
pkg_check_modules(bullet REQUIRED bullet)
37+
include_directories(include ${bullet_INCLUDE_DIRS})
3938

4039
ament_add_gtest(buffer_core_test test/buffer_core_test.cpp)
4140
if(TARGET buffer_core_test)
@@ -60,14 +59,16 @@ if(TARGET test_message_filter)
6059
)
6160
endif()
6261

63-
# TODO (ahcorde): activate when tf2_bullet is merged
64-
# ament_add_gtest(test_convert test/test_convert.cpp)
65-
# if(TARGET test_convert)
66-
# ament_target_dependencies(test_convert
67-
# tf2
68-
# tf2_bullet
69-
# )
70-
# endif()
62+
ament_add_gtest(test_convert test/test_convert.cpp)
63+
if(TARGET test_convert)
64+
ament_target_dependencies(test_convert
65+
tf2
66+
tf2_bullet
67+
tf2_eigen
68+
tf2_geometry_msgs
69+
tf2_kdl
70+
)
71+
endif()
7172

7273
ament_add_gtest(test_utils test/test_utils.cpp)
7374
if(TARGET test_utils)

test_tf2/package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,8 @@
1717
<depend>geometry_msgs</depend>
1818
<depend>rclcpp</depend>
1919
<depend>tf2</depend>
20+
<depend>tf2_bullet</depend>
21+
<depend>tf2_eigen</depend>
2022
<depend>tf2_geometry_msgs</depend>
2123
<depend>tf2_kdl</depend>
2224
<depend>tf2_ros</depend>

test_tf2/test/test_convert.cpp

Lines changed: 88 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -38,13 +38,14 @@
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

4344
TEST(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

Comments
 (0)