Skip to content

Commit ac2e2f2

Browse files
committed
Deprecate ToTransform and TransformTo Functions
1 parent ce2bf2a commit ac2e2f2

File tree

5 files changed

+30
-11
lines changed

5 files changed

+30
-11
lines changed

tf2_bullet/include/tf2_bullet/tf2_bullet.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -152,7 +152,9 @@ struct DefaultTransformType<btQuaternion>
152152
* \param[in] t The transform to convert, as a geometry_msgs TransformedStamped message.
153153
* \return The transform message converted to a Bullet btTransform.
154154
*/
155-
inline btTransform transformToBullet(const geometry_msgs::msg::TransformStamped & t)
155+
[[deprecated("Please use tf2::fromMsg()")]]
156+
inline btTransform transformToBullet(
157+
const geometry_msgs::msg::TransformStamped & t)
156158
{
157159
btTransform ans;
158160
fromMsg<>(t.transform, ans);

tf2_eigen/include/tf2_eigen/tf2_eigen.h

Lines changed: 15 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,9 @@ namespace tf2
4747
* \param t The transform to convert, as a geometry_msgs Transform message.
4848
* \return The transform message converted to an Eigen Isometry3d transform.
4949
*/
50-
inline Eigen::Isometry3d transformToEigen(const geometry_msgs::msg::Transform & t)
50+
[[deprecated("Please use tf2::fromMsg()")]]
51+
inline Eigen::Isometry3d transformToEigen(
52+
const geometry_msgs::msg::Transform & t)
5153
{
5254
Eigen::Isometry3d res;
5355
tf2::fromMsg<>(t, res);
@@ -58,17 +60,23 @@ inline Eigen::Isometry3d transformToEigen(const geometry_msgs::msg::Transform &
5860
* \param t The transform to convert, as a geometry_msgs TransformedStamped message.
5961
* \return The transform message converted to an Eigen Isometry3d transform.
6062
*/
63+
[[deprecated("Please use tf2::fromMsg()")]]
6164
inline
62-
Eigen::Isometry3d transformToEigen(const geometry_msgs::msg::TransformStamped & t)
65+
Eigen::Isometry3d transformToEigen(
66+
const geometry_msgs::msg::TransformStamped & t)
6367
{
64-
return transformToEigen(t.transform);
68+
Eigen::Isometry3d res;
69+
tf2::fromMsg<>(t.transform, res);
70+
return res;
6571
}
6672

6773
/** \brief Convert an Eigen Affine3d transform to the equivalent geometry_msgs message type.
6874
* \param T The transform to convert, as an Eigen Affine3d transform.
6975
* \return The transform converted to a TransformStamped message.
7076
*/
71-
inline geometry_msgs::msg::TransformStamped eigenToTransform(const Eigen::Affine3d & T)
77+
[[deprecated("Please use tf2::toMsg()")]]
78+
inline geometry_msgs::msg::TransformStamped
79+
eigenToTransform(const Eigen::Affine3d & T)
7280
{
7381
geometry_msgs::msg::TransformStamped t;
7482
tf2::toMsg<>(T, t.transform);
@@ -79,7 +87,9 @@ inline geometry_msgs::msg::TransformStamped eigenToTransform(const Eigen::Affine
7987
* \param T The transform to convert, as an Eigen Isometry3d transform.
8088
* \return The transform converted to a TransformStamped message.
8189
*/
82-
inline geometry_msgs::msg::TransformStamped eigenToTransform(const Eigen::Isometry3d & T)
90+
[[deprecated("Please use tf2::toMsg()")]]
91+
inline geometry_msgs::msg::TransformStamped
92+
eigenToTransform(const Eigen::Isometry3d & T)
8393
{
8494
geometry_msgs::msg::TransformStamped t;
8595
tf2::toMsg<>(T, t.transform);

tf2_eigen/test/tf2_eigen-test.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -132,7 +132,8 @@ TEST(TfEigen, ConvertTransform)
132132

133133
geometry_msgs::msg::Transform msg;
134134
tf2::toMsg(T, msg);
135-
Eigen::Affine3d Tback = tf2::transformToEigen(msg);
135+
Eigen::Affine3d Tback;
136+
tf2::fromMsg(msg, Tback);
136137

137138
EXPECT_TRUE(T.isApprox(Tback));
138139
EXPECT_TRUE(tm.isApprox(Tback.matrix()));
@@ -141,7 +142,8 @@ TEST(TfEigen, ConvertTransform)
141142
Eigen::Isometry3d I(tm);
142143

143144
tf2::toMsg(T, msg);
144-
Eigen::Isometry3d Iback = tf2::transformToEigen(msg);
145+
Eigen::Isometry3d Iback;
146+
tf2::fromMsg(msg, Iback);
145147

146148
EXPECT_TRUE(I.isApprox(Iback));
147149
EXPECT_TRUE(tm.isApprox(Iback.matrix()));

tf2_geometry_msgs/include/tf2_geometry_msgs/tf2_geometry_msgs.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,8 +62,10 @@ namespace tf2
6262
* \param t TransformStamped message to convert.
6363
* \return The converted KDL Frame.
6464
*/
65+
[[deprecated("Please use tf2::fromMsg()")]]
6566
inline
66-
KDL::Frame gmTransformToKDL(const geometry_msgs::msg::TransformStamped & t)
67+
KDL::Frame
68+
gmTransformToKDL(const geometry_msgs::msg::TransformStamped & t)
6769
{
6870
return KDL::Frame(
6971
KDL::Rotation::Quaternion(

tf2_kdl/include/tf2_kdl/tf2_kdl.h

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,9 @@ namespace tf2
5656
* \param[in] t The transform to convert, as a geometry_msgs TransformedStamped message.
5757
* \return The transform message converted to an KDL Frame.
5858
*/
59-
inline KDL::Frame transformToKDL(const geometry_msgs::msg::TransformStamped & t)
59+
[[deprecated("Please use tf2::fromMsg()")]] inline KDL::Frame
60+
transformToKDL(
61+
const geometry_msgs::msg::TransformStamped & t)
6062
{
6163
KDL::Frame ans;
6264
tf2::fromMsg<>(t.transform, ans);
@@ -67,7 +69,8 @@ inline KDL::Frame transformToKDL(const geometry_msgs::msg::TransformStamped & t)
6769
* \param[in] k The transform to convert, as an KDL Frame.
6870
* \return The transform converted to a TransformStamped message.
6971
*/
70-
inline geometry_msgs::msg::TransformStamped kdlToTransform(const KDL::Frame & k)
72+
[[deprecated("Please use tf2::toMsg()")]] inline geometry_msgs::msg::TransformStamped
73+
kdlToTransform(const KDL::Frame & k)
7174
{
7275
geometry_msgs::msg::TransformStamped ans;
7376
tf2::toMsg<>(k, ans.transform);

0 commit comments

Comments
 (0)