Skip to content

Commit

Permalink
Pose3: deprecate + operator in favor of * (gazebosim#381)
Browse files Browse the repository at this point in the history
The * operator matches the behavior of multiplying
transform matrices, so it should be preferred over
the addition operator, which is confusing.

Part of gazebosim#60.

Signed-off-by: Steve Peters <[email protected]>
  • Loading branch information
scpeters authored Mar 28, 2022
1 parent b1cb6bb commit 71b6db2
Show file tree
Hide file tree
Showing 3 changed files with 31 additions and 13 deletions.
5 changes: 5 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,11 @@ release will remove the deprecated code.
+ ***Deprecation:*** public: void Col(unsigned int, const Vector3<T> &)
+ ***Replacement:*** public: void SetCol(unsigned int, const Vector3<T> &)

1. **Pose3.hh**
+ The addition operators `+` and `+=` are deprecated in favor of multiplication
operators `*` and `*=`, though the order of operands is reversed
(A + B = B * A).

1. **Quaternion.hh**
+ ***Deprecation:*** public: void Axis(T, T, T, T)
+ ***Replacement:*** public: void SetFromAxisAngle(T, T, T, T)
Expand Down
5 changes: 3 additions & 2 deletions include/ignition/math/Pose3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -183,7 +183,7 @@ namespace ignition
/// then, B + A is the transform from O to Q specified in frame O
/// \param[in] _pose Pose3<T> to add to this pose.
/// \return The resulting pose.
public: Pose3<T> operator+(const Pose3<T> &_pose) const
public: IGN_DEPRECATED(7) Pose3<T> operator+(const Pose3<T> &_pose) const
{
Pose3<T> result;

Expand All @@ -197,7 +197,8 @@ namespace ignition
/// \param[in] _pose Pose3<T> to add to this pose.
/// \sa operator+(const Pose3<T> &_pose) const.
/// \return The resulting pose.
public: const Pose3<T> &operator+=(const Pose3<T> &_pose)
public: IGN_DEPRECATED(7) const Pose3<T> &
operator+=(const Pose3<T> &_pose)
{
this->p = this->CoordPositionAdd(_pose);
this->q = this->CoordRotationAdd(_pose.q);
Expand Down
34 changes: 23 additions & 11 deletions src/Pose_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,9 @@

#include <gtest/gtest.h>

#include "ignition/math/Helpers.hh"
#include "ignition/math/Pose3.hh"
#include <ignition/math/Helpers.hh>
#include <ignition/math/Pose3.hh>
#include <ignition/utils/SuppressWarning.hh>

using namespace ignition;

Expand Down Expand Up @@ -61,17 +62,28 @@ TEST(PoseTest, Pose)
// test hypothesis that if
// A is the transform from O to P specified in frame O
// B is the transform from P to Q specified in frame P
// then, B + A is the transform from O to Q specified in frame O
// then, A * B is the transform from O to Q specified in frame O
math::Pose3d A(math::Vector3d(1, 0, 0),
math::Quaterniond(0, 0, IGN_PI/4.0));
math::Pose3d B(math::Vector3d(1, 0, 0),
math::Quaterniond(0, 0, IGN_PI/2.0));
EXPECT_TRUE(math::equal((B + A).Pos().X(), 1.0 + 1.0/sqrt(2)));
EXPECT_TRUE(math::equal((B + A).Pos().Y(), 1.0/sqrt(2)));
EXPECT_TRUE(math::equal((B + A).Pos().Z(), 0.0));
EXPECT_TRUE(math::equal((B + A).Rot().Euler().X(), 0.0));
EXPECT_TRUE(math::equal((B + A).Rot().Euler().Y(), 0.0));
EXPECT_TRUE(math::equal((B + A).Rot().Euler().Z(), 3.0*IGN_PI/4.0));
EXPECT_TRUE(math::equal((A * B).Pos().X(), 1.0 + 1.0/sqrt(2)));
EXPECT_TRUE(math::equal((A * B).Pos().Y(), 1.0/sqrt(2)));
EXPECT_TRUE(math::equal((A * B).Pos().Z(), 0.0));
EXPECT_TRUE(math::equal((A * B).Rot().Euler().X(), 0.0));
EXPECT_TRUE(math::equal((A * B).Rot().Euler().Y(), 0.0));
EXPECT_TRUE(math::equal((A * B).Rot().Euler().Z(), 3.0*IGN_PI/4.0));

IGN_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION
// Coverage for + operator
EXPECT_EQ(A * B, B + A);
EXPECT_NE(A * B, A + B);

// Coverage for += operator
math::Pose3d C(B);
C += A;
EXPECT_EQ(C, A * B);
IGN_UTILS_WARN_RESUME__DEPRECATED_DECLARATION
}
{
// If:
Expand Down Expand Up @@ -135,11 +147,11 @@ TEST(PoseTest, Pose)
EXPECT_TRUE(pose1.Rot() ==
math::Quaterniond(0.946281, -0.0933066, -0.226566, -0.210984));

pose = math::Pose3d(1, 2, 3, .1, .2, .3) + math::Pose3d(4, 5, 6, .4, .5, .6);
pose = math::Pose3d(4, 5, 6, .4, .5, .6) * math::Pose3d(1, 2, 3, .1, .2, .3);
EXPECT_TRUE(pose ==
math::Pose3d(5.74534, 7.01053, 8.62899, 0.675732, 0.535753, 1.01174));

pose += pose;
pose *= pose;
EXPECT_TRUE(pose ==
math::Pose3d(11.314, 16.0487, 15.2559, 1.49463, 0.184295, 2.13932));

Expand Down

0 comments on commit 71b6db2

Please sign in to comment.