Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[parsing] Improve SDFormat inertia handling #19245

Merged

Conversation

rpoyner-tri
Copy link
Contributor

@rpoyner-tri rpoyner-tri commented Apr 22, 2023

This patch brings inertia invalidity reporting under diagnostic policy, and relaxes inertia problems from hard throws to warnings.

The move to diagnostic policy means that inertia warnings give file names and line numbers, which make it easier to fix problems. In the case of SDFormat, this patch demotes the useless error message from the underlying sdformat library to a warning, and emits more detailed warnings in the later translation-to-Drake phase.

The move from hard throws to warnings means that models with non-physical inertias can still be used with non-simulation workflows, such as visualization, kinematics, and analysis.


This change is Reviewable

Copy link
Contributor Author

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

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

See #18773 for discussion and context.

Reviewable status: needs platform reviewer assigned, needs at least two assigned reviewers, missing label for release notes

Copy link
Contributor Author

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

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

#19238 is the analogous patch for URDF.

Reviewable status: needs platform reviewer assigned, needs at least two assigned reviewers, missing label for release notes

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

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

Reviewed 2 of 2 files at r1, all commit messages.
Reviewable status: needs platform reviewer assigned, needs at least two assigned reviewers, missing label for release notes (waiting on @rpoyner-tri)

Copy link
Contributor Author

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

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

Reviewable status: 1 unresolved discussion, needs platform reviewer assigned, needs at least two assigned reviewers, missing label for release notes (waiting on @jwnimmer-tri)

a discussion (no related file):
This patch in r1 has the same "dummy inertia" choice as the URDF patch -- there is ongoing discussion there. This patch should follow the resolution of that discussion.


Copy link
Contributor Author

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

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

Reviewable status: 2 unresolved discussions, needs platform reviewer assigned, needs at least two assigned reviewers, missing label for release notes (waiting on @jwnimmer-tri)


multibody/parsing/test/detail_sdf_parser_test.cc line 522 at r2 (raw file):

  </link>
</model>)""");
  EXPECT_THAT(TakeWarning(), ::testing::MatchesRegex(expected_message));

I'm not convinced this is the right resolution, but it rolls with the spirit of "received file inertias are almost always garbage; don't prevent kinematics and other workflows".

Copy link
Contributor Author

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

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

Reviewable status: 2 unresolved discussions, needs platform reviewer assigned, needs at least two assigned reviewers, missing label for release notes (waiting on @jwnimmer-tri and @rpoyner-tri)

a discussion (no related file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

This patch in r1 has the same "dummy inertia" choice as the URDF patch -- there is ongoing discussion there. This patch should follow the resolution of that discussion.

Some considerations so far:

  • It probably makes sense to carve out the portion of the code that has both the "magic" catch blocks, and the dummy inertia. Even at "rule of 2", it's magic enough code that sharing would be worth the trouble.
  • [parsing] Improve URDF inertia invalidity handling #19238 as it is so far likely needs some sanity testing on the dummy inertia.
  • perhaps this PR can take on the task of separating out the inertia building, and the related unit test to a new shared location.

Copy link
Contributor Author

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

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

+(status: do not review) while the URDF patch percolates.

Reviewable status: 2 unresolved discussions, needs platform reviewer assigned, needs at least two assigned reviewers, missing label for release notes (waiting on @jwnimmer-tri)

@rpoyner-tri rpoyner-tri changed the title [parsing] Improve SDFormat inertia invalidity reporting [parsing] Improve SDFormat inertia handling May 2, 2023
@rpoyner-tri rpoyner-tri added release notes: fix This pull request contains fixes (no new features) and removed status: do not review labels May 2, 2023
Copy link
Contributor Author

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

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

-(status: do not review) +(release notes: fix)
+@amcastro-tri for feature review, based on his high number of surviving code lines in detail_sdf_parser.cc, and not being today's on-call platform reviewer.
FYI @mitiguy -- shouldn't be much new math, only moved math.

Reviewable status: 2 unresolved discussions, LGTM missing from assignee amcastro-tri, needs platform reviewer assigned, needs at least two assigned reviewers (waiting on @amcastro-tri)

Copy link
Contributor

@amcastro-tri amcastro-tri left a comment

Choose a reason for hiding this comment

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

at this point a few questions only

Reviewed 1 of 8 files at r3.
Reviewable status: 11 unresolved discussions, LGTM missing from assignee amcastro-tri, needs platform reviewer assigned, needs at least two assigned reviewers (waiting on @rpoyner-tri)


multibody/parsing/detail_common.h line 218 at r3 (raw file):

// This helper struct serves to label and order the inertia inputs in the
// (otherwise unmanageable) parameter list of ParseSpatialInertia.

minor, it's not unmanageable thanks to you! so I'd keep the docs to "Helper struct to store inputs for the components of a rotational inertia."


multibody/parsing/detail_common.h line 219 at r3 (raw file):

// This helper struct serves to label and order the inertia inputs in the
// (otherwise unmanageable) parameter list of ParseSpatialInertia.
struct InertiaInputs {

nit, suggestoin, you could store mass here and make this an in-memory representation of a full spatial inertia, less arguments for ParseSpatialInertia()


multibody/parsing/detail_common.h line 224 at r3 (raw file):

  double iyy{};
  double izz{};
  // Products of inertia.

could you state units here? sometimes people do include mass as in kg⋅m², and sometimes only m².


multibody/parsing/detail_common.h line 232 at r3 (raw file):

// Combines the given user inputs into a SpatialInertia. When any data is
// invalid, emits a warning into the diagnostic policy and returns a
// best-effort approximation instead.

I haven't read the source yet, but why to return a "best-effort approximation"? that'd require to document whatev heuristics are required to accomplish that.
As far as I understood from your PR description, invalid inertias are allowed so that users can do kinematic things like visualizations.
If the input inertia values are invalid and therefore not meant for sim and/or dynamics queries, then probably I'd emit a warning and return an invalid inertia full of NaNs. That way users get bit early, with a trail of NaNs easy to track, and hopefully they get forced to ready your warning.


multibody/parsing/detail_common.h line 234 at r3 (raw file):

// best-effort approximation instead.
// @param diagnostic  The error-reporting channel.
// @param X_BBi       Pose of the inertia frame expressed in the body's frame.

you din't quite define Bi. When I read the inputs to this method my immediate thoughts are:

  1. About what point are inertia_inputs computed? pressumably Bi's origin?
  2. In what frame is inertia_inputs expressed? presumably Bi?
  3. I'd strongly suggest to use monogram notation for inertia_inputs! after all, is an in-memory representation of a rotational inertia. So maybe inertia_inputs_Bi_Bi?

multibody/parsing/detail_common.cc line 257 at r3 (raw file):

  // validity checking happen later.
  const double plausible_dummy_mass =
      (std::isfinite(mass) && mass > 0.0) ? mass : 1.0;

as suggested in the header, I'd make this NaN instead. After all, that'd mean the parsed file is not meant for dynamics computations.


multibody/parsing/detail_common.cc line 265 at r3 (raw file):

  const double plausible_radius =
      std::cbrt((3.0 / (4.0 * M_PI)) * plausible_volume);
  // Create Mdum_BBo_B, a plausible spatial inertia for B about Bo (B's origin).

maybe a dumb question, what's dum?


multibody/parsing/detail_common.cc line 275 at r3 (raw file):

       kPlausibleDensity, plausible_radius);
  // Bi's origin is at the COM as documented in
  // http://wiki.ros.org/urdf/XML/link#Elements

IMO this should be part of your docs in the header. That is, define Bi as being a frame located at the body's CoM, not necessarily aligned with the principal axes of the body (since clearly the producst of inertia are allowed to be non-zero)


multibody/parsing/detail_common.cc line 279 at r3 (raw file):

  const SpatialInertia<double> Mdum_BBo_B = Mdum_BBcm.Shift(-p_BoBcm_B);

  // Yes, catching exceptions violates the coding standard. It is done here to

is there a TODO here?


multibody/parsing/detail_common.cc line 292 at r3 (raw file):

  } catch (const std::exception& e) {
    diagnostic.Warning(e.what());
    return Mdum_BBo_B;

Here and below, I'm proposing to regtunr a NaN inertia, i.e. return SpatialInertia<double>()


multibody/parsing/detail_common.cc line 302 at r3 (raw file):

  }
  // B and Bi are not necessarily aligned.
  const math::RotationMatrix<double> R_BBi(X_BBi.rotation());

nit, you could probably get a reference instead of a copy?

Copy link
Contributor

@amcastro-tri amcastro-tri left a comment

Choose a reason for hiding this comment

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

Reviewed 1 of 8 files at r3.
Reviewable status: 11 unresolved discussions, LGTM missing from assignee amcastro-tri, needs platform reviewer assigned, needs at least two assigned reviewers (waiting on @rpoyner-tri)

@jwnimmer-tri
Copy link
Collaborator

multibody/parsing/detail_common.h line 232 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

I haven't read the source yet, but why to return a "best-effort approximation"? that'd require to document whatev heuristics are required to accomplish that.
As far as I understood from your PR description, invalid inertias are allowed so that users can do kinematic things like visualizations.
If the input inertia values are invalid and therefore not meant for sim and/or dynamics queries, then probably I'd emit a warning and return an invalid inertia full of NaNs. That way users get bit early, with a trail of NaNs easy to track, and hopefully they get forced to ready your warning.

It's to our advantage to still allow dynamics and simulation from slightly-buggy model input files. The simulation might not be great (and maybe will even crash), but making users type in mathematically perfect inertia values is too much of a burden to impose on someone just getting started with Drake.

Copy link
Contributor

@amcastro-tri amcastro-tri left a comment

Choose a reason for hiding this comment

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

Reviewable status: 11 unresolved discussions, LGTM missing from assignee amcastro-tri, needs platform reviewer assigned, needs at least two assigned reviewers (waiting on @rpoyner-tri)


multibody/parsing/detail_common.h line 232 at r3 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

It's to our advantage to still allow dynamics and simulation from slightly-buggy model input files. The simulation might not be great (and maybe will even crash), but making users type in mathematically perfect inertia values is too much of a burden to impose on someone just getting started with Drake.

I agree, that's why we should compute inertia values automatically for them.

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

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

Reviewed 6 of 8 files at r3, all commit messages.
Reviewable status: 12 unresolved discussions, LGTM missing from assignee amcastro-tri, needs platform reviewer assigned, needs at least two assigned reviewers (waiting on @amcastro-tri and @rpoyner-tri)


multibody/parsing/detail_common.h line 232 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

I agree, that's why we should compute inertia values automatically for them.

So the only problem here is that the PR overview incompletely stated the goals, so you can mark yourself resolved here?


multibody/parsing/detail_common.cc line 275 at r3 (raw file):

       kPlausibleDensity, plausible_radius);
  // Bi's origin is at the COM as documented in
  // http://wiki.ros.org/urdf/XML/link#Elements

nit This is an URDF citation. It's not immediately obvious that the same fact holds true for SDFormat (or, any other format that might call this function).

At minimum, even if we don't know the answer we still need to clarify the comment here to reflect the now-wider scope, possibly with TODOs.

Or possibly this comment should remain in the URDF parser and not move here?

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

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

Reviewable status: 12 unresolved discussions, LGTM missing from assignee amcastro-tri, needs platform reviewer assigned, needs at least two assigned reviewers (waiting on @amcastro-tri and @rpoyner-tri)


multibody/parsing/detail_common.h line 232 at r3 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

So the only problem here is that the PR overview incompletely stated the goals, so you can mark yourself resolved here?

Specific example, to help clarify the goal: assume the user has mug.sdf file with a slightly-wrong inertia (i.e., one that we bark about here). They load the mug model and posture it on a table. The robot is off doing something else on a bookshelf nearby, not actually doing anything with the mug. Should we refuse to run the bookshelf simulation because the idle mug on the table had a typo in it's inertia? No, we should still let them run their simulation. We warned them that the mug inertia was not going to be respected. If they they want to ignore that warning for now, we shouldn't get in their way. That means that using NAN for the mug mass and/or inertia would be a detriment to usability.

Copy link
Contributor Author

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

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

Reviewable status: 11 unresolved discussions, LGTM missing from assignee amcastro-tri, needs platform reviewer assigned, needs at least two assigned reviewers (waiting on @amcastro-tri and @rpoyner-tri)


multibody/parsing/detail_common.h line 219 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

nit, suggestoin, you could store mass here and make this an in-memory representation of a full spatial inertia, less arguments for ParseSpatialInertia()

I think adding mass here overinflates a very tiny abstraction. Why not add the offset vector? Why not add physical validity checking? This struct is really just a cheap way to safely transport the rotational inertia components into the parse method, by allowing the ordering to explicit at call sites.


multibody/parsing/detail_common.h line 232 at r3 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

Specific example, to help clarify the goal: assume the user has mug.sdf file with a slightly-wrong inertia (i.e., one that we bark about here). They load the mug model and posture it on a table. The robot is off doing something else on a bookshelf nearby, not actually doing anything with the mug. Should we refuse to run the bookshelf simulation because the idle mug on the table had a typo in it's inertia? No, we should still let them run their simulation. We warned them that the mug inertia was not going to be respected. If they they want to ignore that warning for now, we shouldn't get in their way. That means that using NAN for the mug mass and/or inertia would be a detriment to usability.

  1. The long game is to provide a model-rewriting tool for URDF and SDF, since their published semantics don't support "ignore your silly inertias and compute new ones" the way mujoco's format does.
  2. In the short term, having a warning, and a plausible inertia probably does a better job of avoiding user discouragement than a bag of NaNs. A plausible dummy inertia is visualizable, NaNs are not.

multibody/parsing/detail_common.cc line 257 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

as suggested in the header, I'd make this NaN instead. After all, that'd mean the parsed file is not meant for dynamics computations.

I disagree. See discussions elsewhere.


multibody/parsing/detail_common.cc line 265 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

maybe a dumb question, what's dum?

dum` is the shortened form of "dummy" that @mitiguy recommended when revising #19238 for monogram notation.


multibody/parsing/detail_common.cc line 279 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

is there a TODO here?

Not really. The TODO would be something like "undertake a thorough rewrite of all of the inertia classes, and their error handling". The alternatives were explored during development of #19238 . See for example this slack thread.


multibody/parsing/detail_common.cc line 292 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

Here and below, I'm proposing to regtunr a NaN inertia, i.e. return SpatialInertia<double>()

I disagree. How would that be any better than the old status quo of just exploding at parse time?

Copy link
Contributor Author

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

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

Reviewable status: 8 unresolved discussions, LGTM missing from assignee amcastro-tri, needs platform reviewer assigned, needs at least two assigned reviewers (waiting on @amcastro-tri and @rpoyner-tri)


multibody/parsing/detail_common.h line 224 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

could you state units here? sometimes people do include mass as in kg⋅m², and sometimes only m².

Fun fact: neither URDF nor SDFormat docs give a clear statement of units for these quantities, although some URDF tutorial hints at units. I've claimed here they are kg*m^2, since we are passing them directly to the rotational inertia factory method, and since (I presume) all physical quantities in Drake are in SI units.

slug-ft^2 anyone?


multibody/parsing/detail_common.h line 234 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

you din't quite define Bi. When I read the inputs to this method my immediate thoughts are:

  1. About what point are inertia_inputs computed? pressumably Bi's origin?
  2. In what frame is inertia_inputs expressed? presumably Bi?
  3. I'd strongly suggest to use monogram notation for inertia_inputs! after all, is an in-memory representation of a rotational inertia. So maybe inertia_inputs_Bi_Bi?

Done.


multibody/parsing/detail_common.cc line 275 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

IMO this should be part of your docs in the header. That is, define Bi as being a frame located at the body's CoM, not necessarily aligned with the principal axes of the body (since clearly the producst of inertia are allowed to be non-zero)

Done.

Copy link
Contributor

@amcastro-tri amcastro-tri left a comment

Choose a reason for hiding this comment

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

Reviewable status: LGTM missing from assignee amcastro-tri, needs platform reviewer assigned, needs at least two assigned reviewers (waiting on @rpoyner-tri)


multibody/parsing/detail_common.h line 219 at r3 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

I think adding mass here overinflates a very tiny abstraction. Why not add the offset vector? Why not add physical validity checking? This struct is really just a cheap way to safely transport the rotational inertia components into the parse method, by allowing the ordering to explicit at call sites.

fair.


multibody/parsing/detail_common.h line 224 at r3 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

Fun fact: neither URDF nor SDFormat docs give a clear statement of units for these quantities, although some URDF tutorial hints at units. I've claimed here they are kg*m^2, since we are passing them directly to the rotational inertia factory method, and since (I presume) all physical quantities in Drake are in SI units.

slug-ft^2 anyone?

well, it is very common (at least for 2D shapes) to find tables with inertias in units of m^2 (that is, they didivided by the mass). For 3D shapes this does not happen often though. I'd however at least write in the comment "// Moments, units of mass times length squared". Also, in Drake at least, we always use SI units always, so I believe writing kg⋅m² is ok within the Drake context.


multibody/parsing/detail_common.h line 232 at r3 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…
  1. The long game is to provide a model-rewriting tool for URDF and SDF, since their published semantics don't support "ignore your silly inertias and compute new ones" the way mujoco's format does.
  2. In the short term, having a warning, and a plausible inertia probably does a better job of avoiding user discouragement than a bag of NaNs. A plausible dummy inertia is visualizable, NaNs are not.

I agree with point 2 and I do think this is a great step forward. IMO Point 1 is a much longer term effort and it will take a long time to land in Drake.
I think what is missing from that list is an intermediate step: "Automatic computation of inertias given the geoemtry specification and default density, as in the MuJoCo parser".

Per f2f, it looks like both approaches have prons and cons. Giving users default values has the advantage that it allows them to make progress. The con is that this allows them to shoot themselves in the foot since "almost ok" simulation results are extremely difficult to debug.
Per f2f, we'll move on with the default value solution and possibly write a TODO to revert this to NaN's when the automatic computation of intertias from geometry lands.


multibody/parsing/detail_common.cc line 292 at r3 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

I disagree. How would that be any better than the old status quo of just exploding at parse time?

resolved f2f.

Copy link
Contributor Author

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

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

@amcastro-tri are you ready to L G T M ?
+@ggould-tri for platform review, please.

Reviewable status: LGTM missing from assignees amcastro-tri,ggould-tri(platform) (waiting on @amcastro-tri and @ggould-tri)

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

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

Reviewable status: LGTM missing from assignees ggould-tri(platform),amcastro-tri (waiting on @amcastro-tri and @ggould-tri)


multibody/parsing/detail_common.h line 232 at r3 (raw file):

The con is that this allows them to shoot themselves in the foot since "almost ok" simulation results are extremely difficult to debug.

This is mitigated by the fact that we are printing a warning when this mistake happens. I expect that for a lot of users, that will make it a lot easier to debug.

Once we have a tool that rewrites the SDFormat file to have a valid inertia, the warning should be updated to cite that tool (perhaps as part of a wider troubleshooting.html stanza).

TODO... revert this to NaN's when the automatic computation of intertias from geometry lands.

No. Never should the parser add NaNs to the MbP. In the extreme case, we could calculate the moments from the collision geometry, but I don't even think we should do that. Time will tell what works best, but adding NaNs to the plant is never okay in any regime.

Copy link
Contributor

@ggould-tri ggould-tri left a comment

Choose a reason for hiding this comment

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

:lgtm:

Reviewed 1 of 2 files at r1, 6 of 8 files at r3, 2 of 2 files at r4, all commit messages.
Reviewable status: 1 unresolved discussion, LGTM missing from assignee amcastro-tri (waiting on @amcastro-tri)


multibody/parsing/detail_common.h line 222 at r4 (raw file):

// These quantities should have been parsed from the URDF
// `/robot/link/inertial/inertia` tag or from the SDFormat
// `//model/link/inertial/inertia` tag.

FYI: Thank you for getting the '//' right here! :-)
(and throughout)


multibody/parsing/detail_common.cc line 277 at r4 (raw file):

  const SpatialInertia<double> Mdum_BBo_B = Mdum_BBcm.Shift(-p_BoBcm_B);

  // Yes, catching exceptions violates the coding standard. It is done here to

minor:
It seems like you've already weighed up the arguments here, but I cannot avoid commenting:
(1) Would it be better to provide a critique method in RotationalInertia?
(2) Since the primary coding standard concern is that methods cannot be known to be exception safe, should this document the exception safety of the called method?
(3) Would it be better to use a more specific exception type to avoid issuing more serious errors as warnings?

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

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

Reviewable status: 1 unresolved discussion, LGTM missing from assignee amcastro-tri (waiting on @amcastro-tri)


multibody/parsing/detail_common.cc line 277 at r4 (raw file):

Previously, ggould-tri wrote…

minor:
It seems like you've already weighed up the arguments here, but I cannot avoid commenting:
(1) Would it be better to provide a critique method in RotationalInertia?
(2) Since the primary coding standard concern is that methods cannot be known to be exception safe, should this document the exception safety of the called method?
(3) Would it be better to use a more specific exception type to avoid issuing more serious errors as warnings?

I'm somewhat to blame for the "just catch the exception" stance here.

I would support a version of (2). The SpatialInerta classes (i.e., probably UnitInertia as well) should probably promise that they support the "Basic exception guarantee" in their class overview docs -- that any member function of those classes that throws meets that guarantee.

Copy link
Contributor Author

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

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

Reviewable status: 1 unresolved discussion, LGTM missing from assignee amcastro-tri (waiting on @amcastro-tri)


multibody/parsing/detail_common.cc line 277 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

I'm somewhat to blame for the "just catch the exception" stance here.

I would support a version of (2). The SpatialInerta classes (i.e., probably UnitInertia as well) should probably promise that they support the "Basic exception guarantee" in their class overview docs -- that any member function of those classes that throws meets that guarantee.

To be clear, is it now my responsibility to document the "basic exception guarantee" for all the *Inertia classes, or just they safety of the usage here?

Copy link
Contributor

@ggould-tri ggould-tri left a comment

Choose a reason for hiding this comment

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

Reviewable status: 1 unresolved discussion, LGTM missing from assignee amcastro-tri (waiting on @amcastro-tri)


multibody/parsing/detail_common.cc line 277 at r4 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

To be clear, is it now my responsibility to document the "basic exception guarantee" for all the *Inertia classes, or just they safety of the usage here?

I think either would serve the purposes of this file; if it can be guaranteed at all though I'd think it could be guaranteed in the classes rather than here?

Copy link
Contributor

@amcastro-tri amcastro-tri left a comment

Choose a reason for hiding this comment

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

sorry for the delay @rpoyner-tri , between travel, hospital and meetings I had a pretty hectic last few days.
Feature review done. Thanks for the patience, :lgtm:

Reviewed 1 of 2 files at r1, 6 of 8 files at r3, 2 of 2 files at r4, all commit messages.
Reviewable status: 5 unresolved discussions


multibody/parsing/detail_common.h line 232 at r3 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

The con is that this allows them to shoot themselves in the foot since "almost ok" simulation results are extremely difficult to debug.

This is mitigated by the fact that we are printing a warning when this mistake happens. I expect that for a lot of users, that will make it a lot easier to debug.

Once we have a tool that rewrites the SDFormat file to have a valid inertia, the warning should be updated to cite that tool (perhaps as part of a wider troubleshooting.html stanza).

TODO... revert this to NaN's when the automatic computation of intertias from geometry lands.

No. Never should the parser add NaNs to the MbP. In the extreme case, we could calculate the moments from the collision geometry, but I don't even think we should do that. Time will tell what works best, but adding NaNs to the plant is never okay in any regime.

Not sure why we keep talking about a tool to rewrite SDFs (difficult and long term) when there is a much lower hanging fruit; inertias from geometry, always correct.
BTW, Per f2f, this is already resolved.


multibody/parsing/detail_common.h line 241 at r4 (raw file):

// origin at the center of mass of the body, and axes arbitrary, but sometimes
// chosen to zero out the products of inertia. Callers should have previously
// constructed the transform `X_BBi` from the URDF `/robot/link/inertial/origin`

minor,
In case it simplifies your docs, there is no need to refer to either URDF/SDF/MuJoCo or any other file format here. You simply need to define "your choice" of brame Bi, namely: "frame defined to be located a the body's CoM, not necessarily aligned with the principal axes of inertia"


multibody/parsing/detail_common.h line 247 at r4 (raw file):

// @param X_BBi       Pose of the inertia frame expressed in the body's frame.
// @param mass        Mass of the body.
// @param inputs_Bi_Bi The moments and products of inertia, measured and

nit, there is no "measured" for inertias, only "about a point". In this case it'd be "The moments and products of inertia about Bi's origin, expressed in frame Bi"


multibody/parsing/detail_sdf_diagnostic.cc line 90 at r4 (raw file):

bool IsError(const sdf::Error& report) {
  switch (report.Code()) {
    case sdf::ErrorCode::LINK_INERTIA_INVALID:

maybe a dumb question, being unfamiliar with this code, I don't quite see how this change ties to everything else in this PR. Is it tested/exercised


multibody/parsing/test/detail_common_test.cc line 371 at r4 (raw file):

class ParseSpatialInertiaTest : public test::DiagnosticPolicyTestBase {};

// Confirms successful parsing of friction.

nit, copy/pasta comment

Copy link
Contributor Author

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

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

Reviewable status: 5 unresolved discussions


multibody/parsing/detail_sdf_diagnostic.cc line 90 at r4 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

maybe a dumb question, being unfamiliar with this code, I don't quite see how this change ties to everything else in this PR. Is it tested/exercised

This is necessary to avoid the status-quo of the underlying SDFormat library error getting thrown. Here is an example from current master code:

rico@torg:~/checkout/drake$ ROS_PACKAGE_PATH=$HOME/third/kinova-movo/movo_simulation/movo_gazebo bazel-bin/multibody/parsing/parser_manual_test package://movo_gazebo/models/test_zone/model.sdf
parsing package://movo_gazebo/models/test_zone/model.sdf
error: A link named link has invalid inertia.

No source file-and-line, no values, no explanation whatsoever.

With the current PR applied, instead you get this:

rico@torg:~/checkout/drake$ ROS_PACKAGE_PATH=$HOME/third/kinova-movo/movo_simulation/movo_gazebo bazel-bin/multibody/parsing/parser_manual_test -- package://movo_gazebo/models/test_zone/model.sdf
parsing package://movo_gazebo/models/test_zone/model.sdf
warning: A link named link has invalid inertia.
/home/rico/third/kinova-movo/movo_simulation/movo_gazebo/models/test_zone/model.sdf:4: warning: MakeFromMomentsAndProductsOfInertia(): The rotational inertia
[  0    0    0]
[  0    0    0]
[  0    0  0.1]
did not pass the test CouldBePhysicallyValid().
The associated principal moments of inertia:
0  0  0.1
do not satisfy the triangle inequality.
/home/rico/third/kinova-movo/movo_simulation/movo_gazebo/models/test_zone/model.sdf:4: error: URI 'model://test_zone/meshes/building.dae' refers to unknown package 'test_zone'

The old, useless, message is still there as a warning. It would take a bit more effort to be rid of it entirely. However, we also get the more informative Drake error message, with the relevant file and line number.

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

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

Reviewable status: 5 unresolved discussions


multibody/parsing/detail_common.h line 232 at r3 (raw file):

... always correct.

No its not. The collision solid is often an approximation of the true geometry and anyway the body is usually not a uniform density.

a tool to rewrite SDFs (difficult and long term)

The tool is neither difficult to write nor to use. Having SDFormat files that can be successfully loaded into simulators besides Drake is important. Adding magic new Drake-specific tags to SDFormat per your proposal is the worse option.

Copy link
Contributor

@amcastro-tri amcastro-tri left a comment

Choose a reason for hiding this comment

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

Reviewable status: 5 unresolved discussions


multibody/parsing/detail_common.h line 232 at r3 (raw file):

The collision solid is often an approximation of the true geometry

True, but significantly better than eyeballing an arbitrary mass and dimensions.

The tool is neither difficult to write nor to use.

That's like music to my ears! can't wait to start using it myself.


multibody/parsing/detail_sdf_diagnostic.cc line 90 at r4 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

This is necessary to avoid the status-quo of the underlying SDFormat library error getting thrown. Here is an example from current master code:

rico@torg:~/checkout/drake$ ROS_PACKAGE_PATH=$HOME/third/kinova-movo/movo_simulation/movo_gazebo bazel-bin/multibody/parsing/parser_manual_test package://movo_gazebo/models/test_zone/model.sdf
parsing package://movo_gazebo/models/test_zone/model.sdf
error: A link named link has invalid inertia.

No source file-and-line, no values, no explanation whatsoever.

With the current PR applied, instead you get this:

rico@torg:~/checkout/drake$ ROS_PACKAGE_PATH=$HOME/third/kinova-movo/movo_simulation/movo_gazebo bazel-bin/multibody/parsing/parser_manual_test -- package://movo_gazebo/models/test_zone/model.sdf
parsing package://movo_gazebo/models/test_zone/model.sdf
warning: A link named link has invalid inertia.
/home/rico/third/kinova-movo/movo_simulation/movo_gazebo/models/test_zone/model.sdf:4: warning: MakeFromMomentsAndProductsOfInertia(): The rotational inertia
[  0    0    0]
[  0    0    0]
[  0    0  0.1]
did not pass the test CouldBePhysicallyValid().
The associated principal moments of inertia:
0  0  0.1
do not satisfy the triangle inequality.
/home/rico/third/kinova-movo/movo_simulation/movo_gazebo/models/test_zone/model.sdf:4: error: URI 'model://test_zone/meshes/building.dae' refers to unknown package 'test_zone'

The old, useless, message is still there as a warning. It would take a bit more effort to be rid of it entirely. However, we also get the more informative Drake error message, with the relevant file and line number.

ah! that's so cool! definitely a great improvement. Thanks for the explanation.

Copy link
Contributor Author

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

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

Dismissed @amcastro-tri from a discussion.
Reviewable status: 4 unresolved discussions


multibody/parsing/detail_sdf_diagnostic.cc line 90 at r4 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

ah! that's so cool! definitely a great improvement. Thanks for the explanation.

Done.

This patch brings inertia invalidity reporting under diagnostic policy,
and relaxes inertia problems from hard throws to warnings.

It leverages the prior, analogous change to URDF parsing, moving the
shared logic (and its testing) to a common component.
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
release notes: fix This pull request contains fixes (no new features)
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants