Skip to content

Commit

Permalink
normalize quaternions on tf2_eigen (#644)
Browse files Browse the repository at this point in the history
Signed-off-by: Paul Gesel <[email protected]>
  • Loading branch information
pac48 authored Jan 25, 2024
1 parent 135fc5a commit eb6f48e
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 17 deletions.
13 changes: 8 additions & 5 deletions test_tf2/test/test_convert.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,15 +106,18 @@ TEST(tf2Convert, kdlBulletROSConversions)

TEST(tf2Convert, ConvertTf2Quaternion)
{
const tf2::Quaternion tq(1, 2, 3, 4);
double epsilon = 1e-9;

tf2::Quaternion tq(1, 2, 3, 4);
tq.normalize();
Eigen::Quaterniond eq;
// TODO(gleichdick): switch to tf2::convert() when it's working
tf2::fromMsg(tf2::toMsg(tq), eq);

EXPECT_EQ(tq.w(), eq.w());
EXPECT_EQ(tq.x(), eq.x());
EXPECT_EQ(tq.y(), eq.y());
EXPECT_EQ(tq.z(), eq.z());
EXPECT_NEAR(tq.w(), eq.w(), epsilon);
EXPECT_NEAR(tq.x(), eq.x(), epsilon);
EXPECT_NEAR(tq.y(), eq.y(), epsilon);
EXPECT_NEAR(tq.z(), eq.z(), epsilon);
}

TEST(tf2Convert, PointVectorDefaultMessagetype)
Expand Down
32 changes: 20 additions & 12 deletions tf2_eigen/include/tf2_eigen/tf2_eigen.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,9 +52,11 @@ namespace tf2
inline
Eigen::Isometry3d transformToEigen(const geometry_msgs::msg::Transform & t)
{
Eigen::Quaterniond quat(t.rotation.w, t.rotation.x, t.rotation.y, t.rotation.z);
quat.normalize();
return Eigen::Isometry3d(
Eigen::Translation3d(t.translation.x, t.translation.y, t.translation.z) *
Eigen::Quaterniond(t.rotation.w, t.rotation.x, t.rotation.y, t.rotation.z));
quat);
}

/** \brief Convert a timestamped transform to the equivalent Eigen data type.
Expand All @@ -79,7 +81,8 @@ geometry_msgs::msg::TransformStamped eigenToTransform(const Eigen::Affine3d & T)
t.transform.translation.y = T.translation().y();
t.transform.translation.z = T.translation().z();

Eigen::Quaterniond q(T.linear()); // assuming that upper 3x3 matrix is orthonormal
Eigen::Quaterniond q(T.linear());
q.normalize();
t.transform.rotation.x = q.x();
t.transform.rotation.y = q.y();
t.transform.rotation.z = q.z();
Expand Down Expand Up @@ -330,6 +333,7 @@ inline
void fromMsg(const geometry_msgs::msg::Quaternion & msg, Eigen::Quaterniond & out)
{
out = Eigen::Quaterniond(msg.w, msg.x, msg.y, msg.z);
out.normalize();
}

/** \brief Apply a geometry_msgs TransformStamped to an Eigen-specific Quaterniond type.
Expand Down Expand Up @@ -466,13 +470,15 @@ geometry_msgs::msg::Vector3 toMsg2(const Eigen::Vector3d & in)
inline
void fromMsg(const geometry_msgs::msg::Pose & msg, Eigen::Affine3d & out)
{
Eigen::Quaterniond quat(
msg.orientation.w,
msg.orientation.x,
msg.orientation.y,
msg.orientation.z);
quat.normalize();
out = Eigen::Affine3d(
Eigen::Translation3d(msg.position.x, msg.position.y, msg.position.z) *
Eigen::Quaterniond(
msg.orientation.w,
msg.orientation.x,
msg.orientation.y,
msg.orientation.z));
quat);
}

/** \brief Convert a Pose message transform type to a Eigen Isometry3d.
Expand All @@ -483,13 +489,15 @@ void fromMsg(const geometry_msgs::msg::Pose & msg, Eigen::Affine3d & out)
inline
void fromMsg(const geometry_msgs::msg::Pose & msg, Eigen::Isometry3d & out)
{
Eigen::Quaterniond quat(
msg.orientation.w,
msg.orientation.x,
msg.orientation.y,
msg.orientation.z);
quat.normalize();
out = Eigen::Isometry3d(
Eigen::Translation3d(msg.position.x, msg.position.y, msg.position.z) *
Eigen::Quaterniond(
msg.orientation.w,
msg.orientation.x,
msg.orientation.y,
msg.orientation.z));
quat);
}

/** \brief Convert a Eigen 6x1 Matrix type to a Twist message.
Expand Down

0 comments on commit eb6f48e

Please sign in to comment.