From 9a3aaa875dd88e6da838cebaf03a021a33d8fa04 Mon Sep 17 00:00:00 2001 From: Ashton Larkin Date: Thu, 11 Mar 2021 12:53:08 -0500 Subject: [PATCH] use new quaternion Equal tolerance method Signed-off-by: Ashton Larkin --- src/systems/physics/Physics.cc | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index f8726e3dec..691e927554 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -245,10 +245,7 @@ class ignition::gazebo::systems::PhysicsPrivate pose3Eql { [](const math::Pose3d &_a, const math::Pose3d &_b) { return _a.Pos().Equal(_b.Pos(), 1e-6) && - math::equal(_a.Rot().X(), _b.Rot().X(), 1e-6) && - math::equal(_a.Rot().Y(), _b.Rot().Y(), 1e-6) && - math::equal(_a.Rot().Z(), _b.Rot().Z(), 1e-6) && - math::equal(_a.Rot().W(), _b.Rot().W(), 1e-6); + _a.Rot().Equal(_b.Rot(), 1e-6); }}; /// \brief AxisAlignedBox equality comparison function.