Skip to content

Commit 5c886e3

Browse files
committed
Reenable Eigen tests
1 parent 455d7bb commit 5c886e3

File tree

1 file changed

+68
-57
lines changed

1 file changed

+68
-57
lines changed

tf2_eigen/test/tf2_eigen-test.cpp

Lines changed: 68 additions & 57 deletions
Original file line numberDiff line numberDiff line change
@@ -34,72 +34,83 @@
3434
#endif
3535

3636
#include <gtest/gtest.h>
37+
#include <geometry_msgs/msg/point.hpp>
38+
#include <geometry_msgs/msg/point_stamped.hpp>
39+
#include <geometry_msgs/msg/pose.hpp>
40+
#include <geometry_msgs/msg/pose_stamped.hpp>
41+
#include <geometry_msgs/msg/transform_stamped.hpp>
3742
#include <rclcpp/clock.hpp>
3843
#include <tf2/convert.h>
44+
#include <tf2/transform_datatypes.h>
3945
#include <tf2_eigen/tf2_eigen.hpp>
4046
#include <tf2_ros/buffer.h>
4147
#include <tf2_ros/transform_listener.h>
4248

49+
#include <Eigen/Geometry>
50+
4351
#include <cmath>
4452
#include <memory>
4553

46-
// TODO(clalancette) Re-enable these tests once we have tf2/convert.h:convert(A, B) implemented
47-
// TEST(TfEigen, ConvertVector3dStamped)
48-
// {
49-
// const tf2::Stamped<Eigen::Vector3d> v(Eigen::Vector3d(1,2,3),
50-
// tf2::TimePoint(std::chrono::seconds(5)), "test");
51-
52-
// tf2::Stamped<Eigen::Vector3d> v1;
53-
// geometry_msgs::msg::PointStamped p1;
54-
// tf2::convert(v, p1);
55-
// tf2::convert(p1, v1);
56-
57-
// EXPECT_EQ(v, v1);
58-
// }
59-
60-
// TEST(TfEigen, ConvertVector3d)
61-
// {
62-
// const Eigen::Vector3d v(1,2,3);
63-
64-
// Eigen::Vector3d v1;
65-
// geometry_msgs::msg::Point p1;
66-
// tf2::convert(v, p1);
67-
// tf2::convert(p1, v1);
68-
69-
// EXPECT_EQ(v, v1);
70-
// }
71-
72-
// TEST(TfEigen, ConvertAffine3dStamped)
73-
// {
74-
// const Eigen::Affine3d v_nonstamped(
75-
// Eigen::Translation3d(1,2,3) * Eigen::AngleAxis<double>(1, Eigen::Vector3d::UnitX()));
76-
// const tf2::Stamped<Eigen::Affine3d> v(
77-
// v_nonstamped, tf2::TimePoint(std::chrono::seconds(42)), "test_frame");
78-
79-
// tf2::Stamped<Eigen::Affine3d> v1;
80-
// geometry_msgs::msg::PoseStamped p1;
81-
// tf2::convert(v, p1);
82-
// tf2::convert(p1, v1);
83-
84-
// EXPECT_EQ(v.translation(), v1.translation());
85-
// EXPECT_EQ(v.rotation(), v1.rotation());
86-
// EXPECT_EQ(v.frame_id_, v1.frame_id_);
87-
// EXPECT_EQ(v.stamp_, v1.stamp_);
88-
// }
89-
90-
// TEST(TfEigen, ConvertAffine3d)
91-
// {
92-
// const Eigen::Affine3d v(
93-
// Eigen::Translation3d(1,2,3) * Eigen::AngleAxis<double>(1, Eigen::Vector3d::UnitX()));
94-
95-
// Eigen::Affine3d v1;
96-
// geometry_msgs::msg::Pose p1;
97-
// tf2::convert(v, p1);
98-
// tf2::convert(p1, v1);
99-
100-
// EXPECT_EQ(v.translation(), v1.translation());
101-
// EXPECT_EQ(v.rotation(), v1.rotation());
102-
// }
54+
TEST(TfEigen, ConvertVector3dStamped)
55+
{
56+
const tf2::Stamped<Eigen::Vector3d> v(Eigen::Vector3d(1, 2, 3), tf2::TimePoint(
57+
std::chrono::seconds(
58+
5)), "test");
59+
60+
tf2::Stamped<Eigen::Vector3d> v1;
61+
geometry_msgs::msg::PointStamped p1;
62+
tf2::convert(v, p1);
63+
tf2::convert(p1, v1);
64+
65+
EXPECT_EQ(v, v1);
66+
}
67+
68+
TEST(TfEigen, ConvertVector3d)
69+
{
70+
const Eigen::Vector3d v(1, 2, 3);
71+
72+
Eigen::Vector3d v1;
73+
geometry_msgs::msg::Point p1;
74+
tf2::convert(v, p1);
75+
tf2::convert(p1, v1);
76+
77+
EXPECT_EQ(v, v1);
78+
}
79+
80+
TEST(TfEigen, ConvertAffine3dStamped)
81+
{
82+
const Eigen::Affine3d v_nonstamped(Eigen::Translation3d(1, 2, 3) * Eigen::AngleAxis<double>(
83+
1,
84+
Eigen::Vector3d::UnitX()));
85+
const tf2::Stamped<Eigen::Affine3d> v(v_nonstamped, tf2::TimePoint(
86+
std::chrono::seconds(
87+
42)), "test_frame");
88+
89+
tf2::Stamped<Eigen::Affine3d> v1;
90+
geometry_msgs::msg::PoseStamped p1;
91+
tf2::convert(v, p1);
92+
tf2::convert(p1, v1);
93+
94+
EXPECT_EQ(v.translation(), v1.translation());
95+
EXPECT_EQ(v.rotation(), v1.rotation());
96+
EXPECT_EQ(v.frame_id_, v1.frame_id_);
97+
EXPECT_EQ(v.stamp_, v1.stamp_);
98+
}
99+
100+
TEST(TfEigen, ConvertAffine3d)
101+
{
102+
const Eigen::Affine3d v(Eigen::Translation3d(1, 2, 3) * Eigen::AngleAxis<double>(
103+
1,
104+
Eigen::Vector3d::UnitX()));
105+
106+
Eigen::Affine3d v1;
107+
geometry_msgs::msg::Pose p1;
108+
tf2::convert(v, p1);
109+
tf2::convert(p1, v1);
110+
111+
EXPECT_EQ(v.translation(), v1.translation());
112+
EXPECT_EQ(v.rotation(), v1.rotation());
113+
}
103114

104115
TEST(TfEigen, ConvertTransform)
105116
{

0 commit comments

Comments
 (0)