Skip to content

MassMatrix3: fix bug in PrincipalAxesOffset tolerances#424

Merged
scpeters merged 5 commits intogazebosim:ign-math6from
scpeters:mass_matrix3_tolerance_bug
May 10, 2022
Merged

MassMatrix3: fix bug in PrincipalAxesOffset tolerances#424
scpeters merged 5 commits intogazebosim:ign-math6from
scpeters:mass_matrix3_tolerance_bug

Conversation

@scpeters
Copy link
Copy Markdown
Member

@scpeters scpeters commented May 6, 2022

🦟 Bug fix

Fixes a bug in the tolerances used by MassMatrix3::PrincipalAxesOffset

Summary

The MassMatrix3::PrincipalAxesOffset API accepts a relative tolerance parameter _tol (default 1e-6) but was erroneously using the local variable tol when calling PrincipalMoments. This was causing inertia visuals to render improperly, with the EquivalentBox rotation not matching the principal moments. This includes new tests to cover the relative tolerance behavior and demonstrate the bug (build and run tests for 3776a65 to confirm) and fixes it in 478ccf8. The fix could have been just one character (tol -> _tol), but I moved the statement up above the definition of tol just to be safe.

Checklist

  • Signed all commits for DCO
  • Added tests
  • Updated documentation (as needed)
  • Updated migration guide (as needed)
  • Consider updating Python bindings (if the library has them)
  • codecheck passed (See contributing)
  • All tests passed (See test coverage)
  • While waiting for a review on your PR, please help review another open pull request to support the maintainers

Note to maintainers: Remember to use Squash-Merge and edit the commit message to match the pull request summary while retaining Signed-off-by messages.

scpeters added 2 commits May 5, 2022 17:29
There is an error in the way tolerances are computed
in the PrincipalAxesOffset API, and I've added a
more tests for the tolerance parameter to the
PrincipalAxes* APIs, which include failing test cases
to illustrate the bug.

Signed-off-by: Steve Peters <scpeters@openrobotics.org>
The relative tolerance was not being used when calling
PrincipalMoments, so use it properly.

Signed-off-by: Steve Peters <scpeters@openrobotics.org>
@scpeters scpeters requested a review from chapulina May 6, 2022 00:39
@github-actions github-actions bot added Gazebo 1️1️ Dependency of Gazebo classic version 11 🏯 fortress Ignition Fortress 🏰 citadel Ignition Citadel labels May 6, 2022
@codecov
Copy link
Copy Markdown

codecov bot commented May 6, 2022

Codecov Report

Merging #424 (40fe3c4) into ign-math6 (c52a3fa) will not change coverage.
The diff coverage is n/a.

@@            Coverage Diff             @@
##           ign-math6     #424   +/-   ##
==========================================
  Coverage      99.83%   99.83%           
==========================================
  Files             41       41           
  Lines           4138     4138           
==========================================
  Hits            4131     4131           
  Misses             7        7           
Impacted Files Coverage Δ
...nclude/ignition/math6/ignition/math/MassMatrix3.hh 99.40% <0.00%> (ø)

Continue to review full report at Codecov.

Legend - Click here to learn more
Δ = absolute <relative> (impact), ø = not affected, ? = missing data
Powered by Codecov. Last update c52a3fa...40fe3c4. Read the comment docs.

Copy link
Copy Markdown
Contributor

@chapulina chapulina left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Works for me, thanks for the quick fix!

Copy link
Copy Markdown
Contributor

@chapulina chapulina left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Actually no, wait, I'm checking something here

@chapulina
Copy link
Copy Markdown
Contributor

I was mistaken before, this doesn't fix the issue for me. I just tried your reproduction steps with this branch and it didn't work:

from ignition.math import MassMatrix3d
from ignition.math import Vector3d, Quaterniond

mm3 = MassMatrix3d()
mm3.set_mass(605)
mm3.set_ixx(3219)
mm3.set_iyy(3219)
mm3.set_izz(7.28)
mm3.set_ixy(-0.43)
mm3.set_ixz(-2.56)
mm3.set_iyz(3.37)

size = Vector3d()
rot = Quaterniond()
mm3.equivalent_box(size, rot)

print(size)

The output is

7.98598 0.284122 0.252113

But I'd expect Z >> X and Z >> Y

@scpeters
Copy link
Copy Markdown
Member Author

scpeters commented May 6, 2022

But I'd expect Z >> X and Z >> Y

you need to consider the orientation rot as well. There are multiple equivalent combinations of box size and rot parameters. If the matrix is already diagonalized for the given tolerances, an identity quaternion is returned along with the original ordering of diagonal components. However, if it is not already diagonal, then the principal moments are sorted from smallest to largest and the box orientation is computed accordingly.

@codecov
Copy link
Copy Markdown

codecov bot commented May 9, 2022

Codecov Report

Merging #424 (31f4345) into ign-math6 (b330afe) will not change coverage.
The diff coverage is n/a.

@@            Coverage Diff             @@
##           ign-math6     #424   +/-   ##
==========================================
  Coverage      99.83%   99.83%           
==========================================
  Files             41       41           
  Lines           4138     4138           
==========================================
  Hits            4131     4131           
  Misses             7        7           
Impacted Files Coverage Δ
...nclude/ignition/math6/ignition/math/MassMatrix3.hh 99.40% <0.00%> (ø)

Continue to review full report at Codecov.

Legend - Click here to learn more
Δ = absolute <relative> (impact), ø = not affected, ? = missing data
Powered by Codecov. Last update b330afe...31f4345. Read the comment docs.

Signed-off-by: Steve Peters <scpeters@openrobotics.org>
@scpeters
Copy link
Copy Markdown
Member Author

But I'd expect Z >> X and Z >> Y

you need to consider the orientation rot as well. There are multiple equivalent combinations of box size and rot parameters. If the matrix is already diagonalized for the given tolerances, an identity quaternion is returned along with the original ordering of diagonal components. However, if it is not already diagonal, then the principal moments are sorted from smallest to largest and the box orientation is computed accordingly.

@chapulina I added an additional expectation to a test case for EquivalentBox in 31f4345 that should illustrate how the rotation affects the size vector

Copy link
Copy Markdown
Contributor

@chapulina chapulina left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok, this does solve the inertia visualization issue I had. I think that my workspace got messed up halfway and it looked like it didn't, but it did.

Sorry for the noise and thanks for the quick fix!

@scpeters scpeters merged commit 3da7b4f into gazebosim:ign-math6 May 10, 2022
@scpeters scpeters deleted the mass_matrix3_tolerance_bug branch May 10, 2022 21:31
@scpeters scpeters mentioned this pull request May 10, 2022
7 tasks
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

🏰 citadel Ignition Citadel 🏯 fortress Ignition Fortress Gazebo 1️1️ Dependency of Gazebo classic version 11

Projects

Archived in project

Development

Successfully merging this pull request may close these issues.

4 participants