Skip to content

Commit 0a9f496

Browse files
committed
Add test for Vector/Point toMsg()
1 parent f049ad8 commit 0a9f496

File tree

3 files changed

+110
-19
lines changed

3 files changed

+110
-19
lines changed

test_tf2/CMakeLists.txt

Lines changed: 12 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -24,19 +24,14 @@ 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})
39-
4035
ament_add_gtest(buffer_core_test test/buffer_core_test.cpp)
4136
if(TARGET buffer_core_test)
4237
ament_target_dependencies(buffer_core_test
@@ -60,14 +55,16 @@ if(TARGET test_message_filter)
6055
)
6156
endif()
6257

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()
58+
ament_add_gtest(test_convert test/test_convert.cpp)
59+
if(TARGET test_convert)
60+
ament_target_dependencies(test_convert
61+
tf2
62+
tf2_bullet
63+
tf2_eigen
64+
tf2_geometry_msgs
65+
tf2_kdl
66+
)
67+
endif()
7168

7269
ament_add_gtest(test_utils test/test_utils.cpp)
7370
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: 96 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -35,16 +35,23 @@
3535
* Author: Eitan Marder-Eppstein
3636
*********************************************************************/
3737
#include <gtest/gtest.h>
38+
#include <geometry_msgs/msg/point_stamped.hpp>
39+
#include <geometry_msgs/msg/point.hpp>
40+
#include <geometry_msgs/msg/vector3.hpp>
3841
#include <tf2/convert.h>
42+
#include <tf2/LinearMath/Quaternion.h>
3943
#include <tf2_kdl/tf2_kdl.hpp>
4044
#include <tf2_bullet/tf2_bullet.hpp>
45+
#include <tf2_eigen/tf2_eigen.hpp>
4146
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
4247

48+
#include <Eigen/Geometry>
49+
4350
TEST(tf2Convert, kdlToBullet)
4451
{
4552
double epsilon = 1e-9;
4653

47-
tf2::Stamped<btVector3> b(btVector3(1,2,3), tf2::timeFromSec(0), "my_frame");
54+
tf2::Stamped<btVector3> b(btVector3(1, 2, 3), tf2::timeFromSec(0), "my_frame");
4855

4956
tf2::Stamped<btVector3> b1 = b;
5057
tf2::Stamped<KDL::Vector> k1;
@@ -71,11 +78,12 @@ TEST(tf2Convert, kdlBulletROSConversions)
7178
{
7279
double epsilon = 1e-9;
7380

74-
tf2::Stamped<btVector3> b1(btVector3(1,2,3), tf2::timeFromSec(0), "my_frame"), b2, b3, b4;
81+
tf2::Stamped<btVector3> b1(btVector3(1, 2, 3), tf2::timeFromSec(0), "my_frame"), b2, b3, b4;
7582
geometry_msgs::msg::PointStamped r1, r2, r3;
7683
tf2::Stamped<KDL::Vector> k1, k2, k3;
7784

78-
// Do bullet -> self -> bullet -> KDL -> self -> KDL -> ROS -> self -> ROS -> KDL -> bullet -> ROS -> bullet
85+
// Do bullet -> self -> bullet -> KDL -> self -> KDL -> ROS -> self
86+
// -> ROS -> KDL -> bullet -> ROS -> bullet
7987
tf2::convert(b1, b1);
8088
tf2::convert(b1, b2);
8189
tf2::convert(b2, k1);
@@ -96,7 +104,91 @@ TEST(tf2Convert, kdlBulletROSConversions)
96104
EXPECT_NEAR(b1.z(), b4.z(), epsilon);
97105
}
98106

99-
int main(int argc, char** argv)
107+
TEST(tf2Convert, ConvertTf2Quaternion)
108+
{
109+
const tf2::Quaternion tq(1, 2, 3, 4);
110+
Eigen::Quaterniond eq;
111+
// TODO(gleichdick): switch to tf2::convert() when it's working
112+
tf2::fromMsg(tf2::toMsg(tq), eq);
113+
114+
EXPECT_EQ(tq.w(), eq.w());
115+
EXPECT_EQ(tq.x(), eq.x());
116+
EXPECT_EQ(tq.y(), eq.y());
117+
EXPECT_EQ(tq.z(), eq.z());
118+
}
119+
120+
TEST(tf2Convert, PointVectorDefaultMessagetype)
121+
{
122+
// Verify the return type of `toMsg()`
123+
// as it can return a Vector3 or a Point for certain datatypes
124+
{
125+
// Bullet
126+
const tf2::Stamped<btVector3> b1{btVector3{1.0, 3.0, 4.0}, tf2::TimePoint(), "my_frame"};
127+
const geometry_msgs::msg::PointStamped msg = tf2::toMsg(b1);
128+
129+
EXPECT_EQ(msg.point.x, 1.0);
130+
EXPECT_EQ(msg.point.y, 3.0);
131+
EXPECT_EQ(msg.point.z, 4.0);
132+
EXPECT_EQ(msg.header.frame_id, b1.frame_id_);
133+
}
134+
{
135+
// Eigen
136+
const Eigen::Vector3d e1{2.0, 4.0, 5.0};
137+
const geometry_msgs::msg::Point msg = tf2::toMsg(e1);
138+
139+
EXPECT_EQ(msg.x, 2.0);
140+
EXPECT_EQ(msg.y, 4.0);
141+
EXPECT_EQ(msg.z, 5.0);
142+
}
143+
{
144+
// tf2
145+
const tf2::Vector3 t1{2.0, 4.0, 5.0};
146+
const geometry_msgs::msg::Vector3 msg = tf2::toMsg(t1);
147+
148+
EXPECT_EQ(msg.x, 2.0);
149+
EXPECT_EQ(msg.y, 4.0);
150+
EXPECT_EQ(msg.z, 5.0);
151+
}
152+
{
153+
// KDL
154+
const tf2::Stamped<KDL::Vector> k1{KDL::Vector{1.0, 3.0, 4.0}, tf2::TimePoint(), "my_frame"};
155+
const geometry_msgs::msg::PointStamped msg = tf2::toMsg(k1);
156+
157+
EXPECT_EQ(msg.point.x, 1.0);
158+
EXPECT_EQ(msg.point.y, 3.0);
159+
EXPECT_EQ(msg.point.z, 4.0);
160+
EXPECT_EQ(msg.header.frame_id, k1.frame_id_);
161+
}
162+
}
163+
164+
TEST(tf2Convert, PointVectorOtherMessagetype)
165+
{
166+
{
167+
const tf2::Vector3 t1{2.0, 4.0, 5.0};
168+
geometry_msgs::msg::Point msg;
169+
const geometry_msgs::msg::Point & msg2 = tf2::toMsg(t1, msg);
170+
171+
// returned reference is second argument
172+
EXPECT_EQ(&msg2, &msg);
173+
EXPECT_EQ(msg.x, 2.0);
174+
EXPECT_EQ(msg.y, 4.0);
175+
EXPECT_EQ(msg.z, 5.0);
176+
}
177+
{
178+
// Eigen
179+
const Eigen::Vector3d e1{2.0, 4.0, 5.0};
180+
geometry_msgs::msg::Vector3 msg;
181+
const geometry_msgs::msg::Vector3 & msg2 = tf2::toMsg(e1, msg);
182+
183+
// returned reference is second argument
184+
EXPECT_EQ(&msg2, &msg);
185+
EXPECT_EQ(msg.x, 2.0);
186+
EXPECT_EQ(msg.y, 4.0);
187+
EXPECT_EQ(msg.z, 5.0);
188+
}
189+
}
190+
191+
int main(int argc, char ** argv)
100192
{
101193
testing::InitGoogleTest(&argc, argv);
102194
return RUN_ALL_TESTS();

0 commit comments

Comments
 (0)