Skip to content

Commit

Permalink
Re-enable unstamped eigen tests
Browse files Browse the repository at this point in the history
they were disabled because of MSVC and ADL
(MSVC couldn't choose between tf2::toMsg and Eigen::toMsg)
  • Loading branch information
gleichdick committed May 29, 2021
1 parent a9b6d67 commit 3951ce6
Showing 1 changed file with 21 additions and 22 deletions.
43 changes: 21 additions & 22 deletions tf2_eigen/test/tf2_eigen-test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,18 +65,17 @@ TEST(TfEigen, ConvertVector3dStamped)
EXPECT_EQ(v, v1);
}

// TODO(clalancette) Re-enable these tests once we have tf2/convert.h:convert(A, B) implemented
// TEST(TfEigen, ConvertVector3d)
// {
// const Eigen::Vector3d v(1,2,3);
TEST(TfEigen, ConvertVector3d)
{
const Eigen::Vector3d v(1, 2, 3);

// Eigen::Vector3d v1;
// geometry_msgs::msg::Point p1;
// tf2::convert(v, p1);
// tf2::convert(p1, v1);
Eigen::Vector3d v1;
geometry_msgs::msg::Point p1;
tf2::convert(v, p1);
tf2::convert(p1, v1);

// EXPECT_EQ(v, v1);
// }
EXPECT_EQ(v, v1);
}

TEST(TfEigen, ConvertAffine3dStamped)
{
Expand All @@ -98,20 +97,20 @@ TEST(TfEigen, ConvertAffine3dStamped)
EXPECT_EQ(v.stamp_, v1.stamp_);
}

// TODO(clalancette) Re-enable these tests once we have tf2/convert.h:convert(A, B) implemented
// TEST(TfEigen, ConvertAffine3d)
// {
// const Eigen::Affine3d v(
// Eigen::Translation3d(1,2,3) * Eigen::AngleAxis<double>(1, Eigen::Vector3d::UnitX()));
TEST(TfEigen, ConvertAffine3d)
{
const Eigen::Affine3d v(Eigen::Translation3d(1, 2, 3) * Eigen::AngleAxis<double>(
1,
Eigen::Vector3d::UnitX()));

// Eigen::Affine3d v1;
// geometry_msgs::msg::Pose p1;
// tf2::convert(v, p1);
// tf2::convert(p1, v1);
Eigen::Affine3d v1;
geometry_msgs::msg::Pose p1;
tf2::convert(v, p1);
tf2::convert(p1, v1);

// EXPECT_EQ(v.translation(), v1.translation());
// EXPECT_EQ(v.rotation(), v1.rotation());
// }
EXPECT_EQ(v.translation(), v1.translation());
EXPECT_EQ(v.rotation(), v1.rotation());
}

TEST(TfEigen, ConvertTransform)
{
Expand Down

0 comments on commit 3951ce6

Please sign in to comment.