From b6b617a3c0259655e3e61872644416261a65d8f4 Mon Sep 17 00:00:00 2001 From: Martin Pecka Date: Tue, 5 Mar 2019 02:30:04 +0100 Subject: [PATCH] tf2_eigen: Deprecate methods using Affine3d. --- tf2_eigen/include/tf2_eigen/tf2_eigen.h | 27 ++++++++++++++++--------- 1 file changed, 18 insertions(+), 9 deletions(-) diff --git a/tf2_eigen/include/tf2_eigen/tf2_eigen.h b/tf2_eigen/include/tf2_eigen/tf2_eigen.h index f2bc67120..209dcf2f5 100644 --- a/tf2_eigen/include/tf2_eigen/tf2_eigen.h +++ b/tf2_eigen/include/tf2_eigen/tf2_eigen.h @@ -62,9 +62,10 @@ Eigen::Isometry3d transformToEigen(const geometry_msgs::TransformStamped& t) { /** \brief Convert an Eigen Affine3d transform to the equivalent geometry_msgs message type. * \param T The transform to convert, as an Eigen Affine3d transform. * \return The transform converted to a TransformStamped message. + * \deprecated Use Isometry3d instead. */ inline -geometry_msgs::TransformStamped eigenToTransform(const Eigen::Affine3d& T) +ROS_DEPRECATED geometry_msgs::TransformStamped eigenToTransform(const Eigen::Affine3d& T) { geometry_msgs::TransformStamped t; t.transform.translation.x = T.translation().x(); @@ -223,12 +224,14 @@ void fromMsg(const geometry_msgs::PointStamped& msg, tf2::Stamped inline -void doTransform(const Eigen::Affine3d& t_in, - Eigen::Affine3d& t_out, - const geometry_msgs::TransformStamped& transform) { +ROS_DEPRECATED void doTransform( + const Eigen::Affine3d& t_in, + Eigen::Affine3d& t_out, + const geometry_msgs::TransformStamped& transform) { t_out = Eigen::Affine3d(transformToEigen(transform) * t_in); } @@ -330,9 +333,10 @@ void doTransform(const tf2::Stamped& t_in, * This function is a specialization of the toMsg template defined in tf2/convert.h. * \param in The Eigen Affine3d to convert. * \return The Eigen transform converted to a Pose message. + * \deprecated Use Isometry3d instead. */ inline -geometry_msgs::Pose toMsg(const Eigen::Affine3d& in) { +ROS_DEPRECATED geometry_msgs::Pose toMsg(const Eigen::Affine3d& in) { geometry_msgs::Pose msg; msg.position.x = in.translation().x(); msg.position.y = in.translation().y(); @@ -380,9 +384,10 @@ geometry_msgs::Pose toMsg(const Eigen::Isometry3d& in) { * This function is a specialization of the toMsg template defined in tf2/convert.h. * \param msg The Pose message to convert. * \param out The pose converted to a Eigen Affine3d. + * \deprecated USe Isometry3d instead. */ inline -void fromMsg(const geometry_msgs::Pose& msg, Eigen::Affine3d& out) { +ROS_DEPRECATED void fromMsg(const geometry_msgs::Pose& msg, Eigen::Affine3d& out) { out = Eigen::Affine3d( Eigen::Translation3d(msg.position.x, msg.position.y, msg.position.z) * Eigen::Quaterniond(msg.orientation.w, @@ -446,10 +451,11 @@ void fromMsg(const geometry_msgs::Twist &msg, Eigen::Matrix& out) { * \param t_in The frame to transform, as a timestamped Eigen Affine3d transform. * \param t_out The transformed frame, as a timestamped Eigen Affine3d transform. * \param transform The timestamped transform to apply, as a TransformStamped message. + * \deprecated Use Isometry3d instead. */ template <> inline -void doTransform(const tf2::Stamped& t_in, +ROS_DEPRECATED void doTransform(const tf2::Stamped& t_in, tf2::Stamped& t_out, const geometry_msgs::TransformStamped& transform) { t_out = tf2::Stamped(transformToEigen(transform) * t_in, transform.header.stamp, transform.header.frame_id); @@ -476,9 +482,10 @@ void doTransform(const tf2::Stamped& t_in, * This function is a specialization of the toMsg template defined in tf2/convert.h. * \param in The timestamped Eigen Affine3d to convert. * \return The Eigen transform converted to a PoseStamped message. + * \deprecated Use Isometry3d instead. */ inline -geometry_msgs::PoseStamped toMsg(const tf2::Stamped& in) +ROS_DEPRECATED geometry_msgs::PoseStamped toMsg(const tf2::Stamped& in) { geometry_msgs::PoseStamped msg; msg.header.stamp = in.stamp_; @@ -501,9 +508,11 @@ geometry_msgs::PoseStamped toMsg(const tf2::Stamped& in) * This function is a specialization of the toMsg template defined in tf2/convert.h. * \param msg The PoseStamped message to convert. * \param out The pose converted to a timestamped Eigen Affine3d. + * \deprecated Use Isometry3d instead. */ inline -void fromMsg(const geometry_msgs::PoseStamped& msg, tf2::Stamped& out) +ROS_DEPRECATED void fromMsg(const geometry_msgs::PoseStamped& msg, + tf2::Stamped& out) { out.stamp_ = msg.header.stamp; out.frame_id_ = msg.header.frame_id;