Skip to content

Commit

Permalink
Pose3: deprecate + operator in favor of *
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 committed Feb 25, 2022
1 parent 04028c9 commit caf941d
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 11 deletions.
6 changes: 4 additions & 2 deletions include/ignition/math/Pose3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <ignition/math/Quaternion.hh>
#include <ignition/math/Vector3.hh>
#include <ignition/math/config.hh>
#include <ignition/utils/SuppressWarning.hh>

namespace ignition
{
Expand Down Expand Up @@ -183,7 +184,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: Pose3<T> IGN_DEPRECATED(7) operator+(const Pose3<T> &_pose) const
{
Pose3<T> result;

Expand All @@ -197,7 +198,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: const Pose3<T> & IGN_DEPRECATED(7)
operator+=(const Pose3<T> &_pose)
{
this->p = this->CoordPositionAdd(_pose);
this->q = this->CoordRotationAdd(_pose.q);
Expand Down
18 changes: 9 additions & 9 deletions src/Pose_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -61,17 +61,17 @@ 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));
}
{
// If:
Expand Down Expand Up @@ -135,11 +135,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 caf941d

Please sign in to comment.