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

[multibody] AddRigidBody defaults to zero inertia when not specified #21198

Merged
merged 1 commit into from
Apr 2, 2024

Conversation

jwnimmer-tri
Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri commented Mar 27, 2024

We want to enable MbP SAP by default, but if the user welded bodies with NaN inertia then the SAP-flavored MbP will throw an exception (whereas previously this was allowed with a continuous-time plant).

Instead of trying to adjust MbP's calculations to somehow work around the NaNs (#21151), we've decided that we must get rid of the NaNs in the first place. That means that now the default constructor for SpatialInertia is footgun, where our users who were using it as the most compact syntax when adding welded bodies will now start to crash with SAP.

We attack this from two sides:

  • MbP::AddRigidBody now offers a default value for the inertia. When users are adding welded bodies where they don't care about it, the new default makes it easy and compact to add the body.

  • Deprecate the footgun SpatialInertia constructor, and in particular use its deprecation message to teach users about the new AddRigidBody suggestion.

Towards #21098 and #21095.

The general approach I took to porting in this PR is:

(1) Unit tests under multibody stick with NaN. In these cases we should be very precise about what we're doing, and I don't want to go figure out how to change anything more nuanced here. This is just a straight, boring porting of the re-spelling. In follow-up PRs, MbP owners are invited to further tune any test cases for their preferences.

(2) Other code not part of multibody (e.g., planning) switches to use the new defaulted MbP::AddRigidBody API. This provides a better example for users who might cargo-cult the unit tests into their own robot code.

FYI per the table at #17446, the only place we need to worry about NaNs is this programmatic API. None of the file formats we import default to NaN.


This change is Reviewable

@jwnimmer-tri jwnimmer-tri added release notes: newly deprecated This pull request contains new deprecations release notes: fix This pull request contains fixes (no new features) labels Mar 27, 2024
@jwnimmer-tri jwnimmer-tri force-pushed the naan branch 2 times, most recently from e34c287 to 14d2dce Compare March 27, 2024 16:58
Copy link
Collaborator Author

@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 44 of 49 files at r1, 9 of 10 files at r2, 19 of 19 files at r3, all commit messages.
Reviewable status: needs platform reviewer assigned, needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)

Copy link
Collaborator Author

@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 1 of 10 files at r2, 2 of 2 files at r4, all commit messages.
Reviewable status: needs platform reviewer assigned, needs at least two assigned reviewers

@jwnimmer-tri jwnimmer-tri marked this pull request as ready for review March 27, 2024 17:40
Copy link
Collaborator Author

@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.

+@sherm1 for feature review, please. (Feel free to start with a design review of the idea so we can straighten that out first, before diving into the code details & tests.)

If you have time available +@mitiguy you're invited to weigh in here as well.

Reviewable status: LGTM missing from assignees sherm1(platform),mitiguy


multibody/tree/rigid_body.cc line 70 at r4 (raw file):

  const double mass = 1.0;
  const double radius = 0.0625;
  return SpatialInertia<double>::SolidSphereWithMass(mass, radius);

FYI I am in no way attached to this default. If dynamics people want something else here, we can easily change it, either now or later.

Copy link
Collaborator Author

@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 assignees mitiguy,sherm1(platform), labeled "do not merge" (waiting on @jwnimmer-tri)

a discussion (no related file):
Working

After we have buy-in on the idea, I'll need to port Anzu vs the new deprecation.


Copy link
Contributor

@mitiguy mitiguy left a comment

Choose a reason for hiding this comment

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

I like that this PR gets rid of the default SpatialInertia constructor and makes it flexible to change Drake's programmatic default nominal spatial inertia.

As repeated below:
For pragmatic reasons, my immediate preference is to choose the default used by URDF and Mujoco (when Mujoco does not have geometry) , i.e., a spatial inertia with zero mass, zero center of mass, and zero inertia matrix as zero early communicates something odd, whereas SDFormat's numbers are more likely to produce sensible-appearing results in certain cases, even if the simulations are nonsense.
Note: Overview of various defaults for file formats is here

However, it seems odd that using SAP creates programmatic errors when spatial inertia is not needed (Drake bug)? Ideally, we could later fix SAP so it does not use spatial inertias when they are not needed. Using other defaults (including zero) can be problematic, with sensible-appearing (but invalid) results, i.e., animation quality vs. simulating reality.

Reviewed 32 of 49 files at r1, 6 of 10 files at r2, 19 of 19 files at r3, 2 of 2 files at r4.
Reviewable status: 2 unresolved discussions, LGTM missing from assignees mitiguy,sherm1(platform), labeled "do not merge" (waiting on @jwnimmer-tri)


geometry/optimization/test/c_iris_collision_geometry_test.cc line 512 at r4 (raw file):

  ProximityProperties proximity_properties{};
  // C-IRIS doesn't care about robot dynamics. Use arbitrary material
  // properties.

FYI: Consider preserving a portion of the deleted comment (below).

Suggestion:

  // C-IRIS doesn't care about robot dynamics. Use arbitrary material
  // properties and default spatial inertia properties.

geometry/optimization/test/c_iris_test_utilities.cc line 43 at r4 (raw file):

  // C-IRIS only considers robot kinematics, not dynamics. So we use an
  // arbitrary inertia.

FYI Consider preserving part of comment.

Suggestion:

  // C-IRIS only considers robot kinematics, not dynamics. So we use 
  // the nominal default inertia for bodyi (i=0, 1, 2, ...).

geometry/optimization/test/c_iris_test_utilities.cc line 135 at r4 (raw file):

  ProximityProperties proximity_properties{};
  // C-IRIS doesn't care about robot dynamics. Use arbitrary material
  // properties.

FYI: Consider preserving comment about default spatial inertia.

Suggestion:

  // C-IRIS doesn't care about robot dynamics. Use arbitrary material
  // properties and the nominal default spatial inertia.

multibody/plant/multibody_plant.h line 1163 at r4 (raw file):

  ///   %MultibodyPlant, computed about the body frame origin `Bo` and expressed
  ///   in the body frame B. When not provided, defaults to a nominal non-zero
  ///   value.

FYI Consider adjusting the comment as we may want to defer convergence on whether or not the default is a zero, non-zero, or infinite value.

Suggestion:

  ///   in the body frame B. When not provided, uses the nominal default value.

multibody/plant/multibody_plant.h line 1169 at r4 (raw file):

      const std::string& name, ModelInstanceIndex model_instance,
      const SpatialInertia<double>& M_BBo_B =
          RigidBody<T>::MakeNominalSpatialInertiaForConstructor()) {

FYI Consider name change and class change.

Suggestion:

SpatialInertia<T>::MakeNominalDefault()) {

multibody/plant/multibody_plant.h line 1210 at r4 (raw file):

  ///   %MultibodyPlant, computed about the body frame origin `Bo` and expressed
  ///   in the body frame B. When not provided, defaults to a nominal non-zero
  ///   value.

FYI Similar as before.

Suggestion:

  ///   in the body frame B. When not provided, uses the nominal default value.

multibody/plant/multibody_plant.h line 1218 at r4 (raw file):

      const std::string& name,
      const SpatialInertia<double>& M_BBo_B =
          RigidBody<T>::MakeNominalSpatialInertiaForConstructor()) {

FYI Consider class name and/or name change.

Suggestion:

      const SpatialInertia<double>& M_BBo_B =
          SpatialInertia<T>::MakeNominalDefault()) {

multibody/plant/test/multibody_plant_test.cc line 3590 at r4 (raw file):

  const RigidBody<double>& cube = plant.AddRigidBody(
      "cube", SpatialInertia<double>(cube_mass, cube_com, cube_unit_inertia));

FYI I am wondering if the next two lines are to test the new default arguments of AddRigidBody(...). Regardless, it would be helpful to provide a comment as to why these lines are here.


multibody/plant/test/multibody_plant_test.cc line 3637 at r4 (raw file):

  // The default inertia should be physically valid and at least 1 gram.
  for (const auto* simple : {&simple_1, &simple_2}) {
    EXPECT_GE(simple->get_mass(*context), 0.001);

FYI Since there are already default inertia properties for various file formats [e.g., URDF mass=0, SDF mass=1, Mujoco (no geometry) mass=0], I think it best to change the mass test to >= 0.

Suggestion:

    EXPECT_GE(simple->get_mass(*context), 0.0);

multibody/tree/rigid_body.h line 201 at r4 (raw file):

  ///   Spatial inertia of this body B about the frame's origin `Bo` and
  ///   expressed in the body frame B. When not provided, defaults to a nominal
  ///   non-zero value.

FYI Comment updated.

Suggestion:

  ///   expressed in the body frame B. When not provided, uses 
  ///   the nominal default value.

multibody/tree/rigid_body.h line 206 at r4 (raw file):

  explicit RigidBody(const std::string& body_name,
                     const SpatialInertia<double>& M_BBo_B =
                         MakeNominalSpatialInertiaForConstructor());

FYI Consider class and name change.

Suggestion:

                     const SpatialInertia<double>& M_BBo_B =
                         SpatialInertia<double>::MakeNominalDefault());

multibody/tree/rigid_body.h line 218 at r4 (raw file):

  ///   Spatial inertia of this body B about the frame's origin `Bo` and
  ///   expressed in the body frame B. When not provided, defaults to a nominal
  ///   non-zero value.

FYI Comment updated.

Suggestion:

  ///   expressed in the body frame B. When not provided, uses the
  ///   nominal default value.

multibody/tree/rigid_body.h line 223 at r4 (raw file):

  RigidBody(const std::string& body_name, ModelInstanceIndex model_instance,
            const SpatialInertia<double>& M_BBo_B =
                MakeNominalSpatialInertiaForConstructor());

FYI Class and/or name change.

Suggestion:

            const SpatialInertia<double>& M_BBo_B =
                SpatialInertia<double>::MakeNominalDefault());

multibody/tree/rigid_body.h line 740 at r4 (raw file):

    return TemplatedDoCloneToScalar(tree_clone);
  }

BTW As Jeremy noted below, this is a placeholder for discussion.

As repeated from Review Discussion (above):
For pragmatic reasons, my immediate preference is to choose the default used by URDF and Mujoco (when Mujoco does not have geometry) , i.e., a spatial inertia with zero mass, zero center of mass, and zero inertia matrix as zero early communicates something odd, whereas SDFormat's numbers are more likely to produce sensible-appearing results in certain cases, even if the simulations are nonsense.
Note: Overview of various defaults for file formats is here

However, it seems odd that using SAP creates programmatic errors when spatial inertia is not needed (Drake bug)? Ideally, we could later fix SAP so it does not use spatial inertias when they are not needed. Using other defaults (including zero) can be problematic, with sensible-appearing (but invalid) results, i.e., animation quality vs. simulating reality.


multibody/tree/rigid_body.cc line 67 at r4 (raw file):

template <typename T>
SpatialInertia<double> RigidBody<T>::MakeNominalSpatialInertiaForConstructor() {

FYI Consider moving this to the SpatialInertia class and changing its name.

Suggestion:

SpatialInertia<double> SpatialInertia<T>::MakeNominalDefault() {

multibody/tree/spatial_inertia.h line 483 at r4 (raw file):

      "to MultibodyPlant, then instead you should omit the SpatialInertia "
      "argument from MultibodyPlant::AddRigidBody in order to use a more "
      "sensible nominal value.")

FYI Wording change.

Suggestion:

      "If you were were only calling this constructor to create an arbitrary  "
      "SpatialInertia for use by MultibodyPlant::AddRigidBody(), then instead "
      "omit the SpatialInertia argument from MultibodyPlant::AddRigidBody() "
      "as it now has a default nominal argument for spatial inertia.")

multibody/tree/test/rigid_body_test.cc line 58 at r4 (raw file):

  EXPECT_EQ(B.name(), "bar");

  // Sanity check that the inertia was at least 1 gram.

FYI Update wording.

Suggestion:

  // Sanity check on the body's mass properties.

multibody/tree/test/rigid_body_test.cc line 59 at r4 (raw file):

  // Sanity check that the inertia was at least 1 gram.
  EXPECT_GE(B.default_spatial_inertia().get_mass(), 0.001);

FYI Change to 0.0

Suggestion:

  EXPECT_GE(B.default_spatial_inertia().get_mass(), 0.0);

multibody/tree/test/rigid_body_test.cc line 61 at r4 (raw file):

  EXPECT_GE(B.default_spatial_inertia().get_mass(), 0.001);
  EXPECT_EQ(B.default_spatial_inertia().get_com(), Vector3d::Zero());
  EXPECT_GE(B.default_mass(), 0.001);

FYI Change to 0.0

Suggestion:

  EXPECT_GE(B.default_mass(), 0.0);

bindings/pydrake/multibody/plant_py.cc line 246 at r4 (raw file):

            py::arg("name"),
            py::arg("M_BBo_B") =
                RigidBody<T>::MakeNominalSpatialInertiaForConstructor(),

FYI Class and name change

Suggestion:

                SpatialInertia<T>::MakeNominalDefault(),

bindings/pydrake/multibody/plant_py.cc line 253 at r4 (raw file):

            py::arg("name"), py::arg("model_instance"),
            py::arg("M_BBo_B") =
                RigidBody<T>::MakeNominalSpatialInertiaForConstructor(),

FYI Class and name change

Suggestion:

            py::arg("M_BBo_B") =
                SpatialInertia<T>::MakeNominalDefault(),

bindings/pydrake/multibody/tree_py.cc line 322 at r4 (raw file):

    cls  // BR
        .def(py::init<const std::string&, const SpatialInertia<double>&>(),
            py::arg("body_name"),

FYI Name and class change may affect code below (two places).

Copy link
Collaborator Author

@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.

Thanks for taking the time, Paul. To summarize, there were 3 main points to Paul's review:

(1) What should the default inertia value for a RigidBody be?

(2) Where should the factory function live that provides for a central, named definition for that value (so that all of the default arguments can site the same thing)?

(3) Resurrecting some comments at non-multibody call sites. (Considered, and rejected.)

Questions 1 & 2 were repeated dozens of times at different locations. To help focus the discussion, I've dismissed all but one copy of each of those. We'll use the rigid_body.h discussion threads as the home for those two discussions.

(There were also a few small typos / etc noted, that I'll deal with after the high-level review concludes. I've set those to "Working" for now.)

I'll let Sherm weigh in on the "zero kg" vs "one kg" BTW thread, before I reply to it myself.

Reviewable status: 4 unresolved discussions, LGTM missing from assignees mitiguy,sherm1(platform), labeled "do not merge"


multibody/tree/rigid_body.h line 218 at r4 (raw file):
I'll copy-paste a more thorough sentence from Paul that was posted on multibody_plant.h, so that we can centralize the discussion here (so I can close out the other thread):

FYI Consider adjusting the comment as we may want to defer convergence on whether or not the default is a zero, non-zero, or infinite value.

To me it is critical to promise the signedness and finiteness of this default inertia. There are huge usability differences to the three choices (zero, nominal non-zero, infinite). We need to choose the best one of those categories, and then promise that as an invaraint. We'll use the other thread (the "BTW" below) to debate what the default should be, and then of course the docs here will follow suit.

So to me, this discussion can be resolved as "no change necessary, beyond what the other discussion would already necessitate". I don't think we can be wishy-washy here.


multibody/tree/rigid_body.h line 223 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI Class and/or name change.

To me, the default value for a RigidBody's inertia is a property of the RigidBody modeling abstraction, not a property SpatialInertia abstract data type. It's tree-modeling thing, not a math thing. There is no intrinsic default for the math, only a default for models. Thus, the SpatialInertia class is the wrong place to govern the default; its only job is the math, not to model an environment, nor interact with parsers, nor etc.

Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

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

Thoughts posted below (mostly in rigid_body.h), PTAL

Reviewed 32 of 49 files at r1, 4 of 10 files at r2, 17 of 19 files at r3, 2 of 2 files at r4, all commit messages.
Reviewable status: 7 unresolved discussions, LGTM missing from assignees mitiguy,sherm1(platform), labeled "do not merge" (waiting on @jwnimmer-tri)


multibody/parsing/detail_urdf_parser.cc line 218 at r4 (raw file):

  } else {
    SpatialInertia<double> M_BBo_B(0, Vector3d::Zero(),
                                   UnitInertia<double>(0, 0, 0));

BTW there should be a SpatialInertia::Zero() static for this.


multibody/plant/test/contact_results_to_lcm_test.cc line 280 at r4 (raw file):

               unordered_map<GeometryId, FullBodyName>* id_to_body,
               FullBodyName ref_name) {
    const auto& body = plant->AddRigidBody(body_name, model_index);

BTW this change already assumes we aren't using urdf/mujoco style zero inertia as the default (since the original test was explicitly trying to avoid zero).


multibody/plant/test/multibody_plant_test.cc line 3635 at r4 (raw file):

                      cube_unit_inertia.get_products()));

  // The default inertia should be physically valid and at least 1 gram.

BTW assumes we've agreed on a non-zero default. Not obviously right to me.


multibody/tree/rigid_body.h line 223 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

To me, the default value for a RigidBody's inertia is a property of the RigidBody modeling abstraction, not a property SpatialInertia abstract data type. It's tree-modeling thing, not a math thing. There is no intrinsic default for the math, only a default for models. Thus, the SpatialInertia class is the wrong place to govern the default; its only job is the math, not to model an environment, nor interact with parsers, nor etc.

I agree w/JN here -- SpatialInertia should supply an assortment of interesting inertias like NaN, Zero, Unitary, Reasonable or whatever. Then MbP should choose one of those as the default for its rigid bodies, based on our estimate of what will provide the best user experience (some tradeoff between avoiding spurious failures and avoiding giving plausible but wrong answers).


multibody/tree/rigid_body.h line 740 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

BTW As Jeremy noted below, this is a placeholder for discussion.

As repeated from Review Discussion (above):
For pragmatic reasons, my immediate preference is to choose the default used by URDF and Mujoco (when Mujoco does not have geometry) , i.e., a spatial inertia with zero mass, zero center of mass, and zero inertia matrix as zero early communicates something odd, whereas SDFormat's numbers are more likely to produce sensible-appearing results in certain cases, even if the simulations are nonsense.
Note: Overview of various defaults for file formats is here

However, it seems odd that using SAP creates programmatic errors when spatial inertia is not needed (Drake bug)? Ideally, we could later fix SAP so it does not use spatial inertias when they are not needed. Using other defaults (including zero) can be problematic, with sensible-appearing (but invalid) results, i.e., animation quality vs. simulating reality.

So far I'm leaning toward zero as the best middle-ground default. That will behave well when anchored to World and when used for kinematics, optimization or whatever but will give terrible, obviously-wrong results if accidentally used for dynamics (and in many cases we could report failure automatically). I'd still be in favor of NaN if our various algorithms were smart enough not to look at irrelevant inertias but I'm not confident we could do that without leaving hidden land mines and bad UX.

There is also good precedent for zero as Paul said (urdf & mujoco), and real world evidence that SDF's default of 1 1 1 can produce weird behavior not easily diagnosed by the user and consequently eating up a bunch of our time to diagnose. Paul points out that a less-extreme default like .01 .01 .01 would be even harder to diagnose -- the behavior could look more realistic but would be just as wrong in general! Seeing a bunch of zeroes (or an error message saying "you can't use zero for dynamics") would be much easier to self-diagnose.


bindings/pydrake/multibody/plant_py.cc line 246 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI Class and name change

RigidBody<T>::DefaultSpatialInertia() would be my preference

Copy link
Collaborator Author

@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 4 of 5 files at r5, all commit messages.
Reviewable status: 6 unresolved discussions, LGTM missing from assignees mitiguy,sherm1(platform), labeled "do not merge", commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)


multibody/parsing/detail_urdf_parser.cc line 218 at r4 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW there should be a SpatialInertia::Zero() static for this.

Done. (I'll plan for us to keep the Zero() factory even if its not elected as the default.)


multibody/plant/test/contact_results_to_lcm_test.cc line 280 at r4 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW this change already assumes we aren't using urdf/mujoco style zero inertia as the default (since the original test was explicitly trying to avoid zero).

Isn't that line of thinking making my case against zero as a default?

I guess I'll learn more as I experiment with trying out zero. Maybe the comment was stale.


multibody/tree/rigid_body.h line 740 at r4 (raw file):
Understood.

I probably balance the trade-offs differently than you two. For me, crashing is a cardinal usability sin, and should be strongly avoided, especially for first-time users and basic use cases. It prevents them from even looking at the scene in a visualizer at all! They have no easy way to debug anything. They just have a bash prompt and a RuntimeError and no tools to help.

On the other hand, if the user didn't write down a inertia when adding a body and we choose 1kg, their cereal box will behave like a 1kg sphere of water, but oh well? That to me is vastly better then ever crashing. At least they can watch it move in a simulator and then iterate to debug it. It's just 1 click away to visualize the inertia and remember that they forgot to provide a value that matches their body. Making new users route around crashes when building their fisher-price-my-first-first simulation seems like bad UX to me.

So the real question is -- does zero crash or not? If it doesn't, then there's not much objection to defaulting to it, given some plausible upside to making mistakes more immediately evident as you note.

Therefore, I will run some experiments with the proposal of zero, and report back here whether it causes users (and especially non-simulation users) to crash. If I recall correctly, it spuriously crashes less than NaN but can still spuriously crash. In any case, I'll find some evidence one way or another.

There is also good precedent for zero as Paul said (urdf & mujoco) ...

I'd offer than most people hate the URDF default. URDF wasn't so much designed as it fell off the back of the truck and now we're stuck with it. The MuJoCo default is not "zero" but rather "however much geometry you have". For this particular MbP API, that analogy is not applicable since RigidBody doesn't consider geometry.

There might be good arguments for "default to zero" (and we'll learn more as I experiment) like the other reasons you provided, but I do not buy the appeal to authority for either of those two file formats.


multibody/tree/spatial_inertia.h line 468 at r5 (raw file):

  /// Initializes mass, center of mass and rotational inertia to zero.
  static SpatialInertia Zero() {

Working

Needs tests, pybind, etc.

Copy link
Collaborator Author

@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 13 of 13 files at r6, all commit messages.
Reviewable status: 3 unresolved discussions, LGTM missing from assignees mitiguy,sherm1(platform), labeled "do not merge"


multibody/plant/test/contact_results_to_lcm_test.cc line 280 at r4 (raw file):

... the original test was explicitly trying to avoid zero ...

Apparently the comment was overly paranoid. Zero is fine.


multibody/plant/test/multibody_plant_test.cc line 3590 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI I am wondering if the next two lines are to test the new default arguments of AddRigidBody(...). Regardless, it would be helpful to provide a comment as to why these lines are here.

Done


multibody/tree/rigid_body.h line 740 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

Understood.

I probably balance the trade-offs differently than you two. For me, crashing is a cardinal usability sin, and should be strongly avoided, especially for first-time users and basic use cases. It prevents them from even looking at the scene in a visualizer at all! They have no easy way to debug anything. They just have a bash prompt and a RuntimeError and no tools to help.

On the other hand, if the user didn't write down a inertia when adding a body and we choose 1kg, their cereal box will behave like a 1kg sphere of water, but oh well? That to me is vastly better then ever crashing. At least they can watch it move in a simulator and then iterate to debug it. It's just 1 click away to visualize the inertia and remember that they forgot to provide a value that matches their body. Making new users route around crashes when building their fisher-price-my-first-first simulation seems like bad UX to me.

So the real question is -- does zero crash or not? If it doesn't, then there's not much objection to defaulting to it, given some plausible upside to making mistakes more immediately evident as you note.

Therefore, I will run some experiments with the proposal of zero, and report back here whether it causes users (and especially non-simulation users) to crash. If I recall correctly, it spuriously crashes less than NaN but can still spuriously crash. In any case, I'll find some evidence one way or another.

There is also good precedent for zero as Paul said (urdf & mujoco) ...

I'd offer than most people hate the URDF default. URDF wasn't so much designed as it fell off the back of the truck and now we're stuck with it. The MuJoCo default is not "zero" but rather "however much geometry you have". For this particular MbP API, that analogy is not applicable since RigidBody doesn't consider geometry.

There might be good arguments for "default to zero" (and we'll learn more as I experiment) like the other reasons you provided, but I do not buy the appeal to authority for either of those two file formats.

So far, zero seems to be passing CI. I cleaned up the branch a bit more so that I can test projects beyond Drake. Still working.

@jwnimmer-tri jwnimmer-tri changed the title [multibody] AddRigidBody offers a default inertia [multibody] AddRigidBody defaults to zero inertia when not specified Mar 28, 2024
Copy link
Collaborator Author

@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.

FYI put the deprecation window at 6 months, since there's not much pain for us for keeping the deprecated constructor in place, and so we might as well give users a longer time to adapt.

This should be ready for full / detailed feature review, now.

Reviewable status: 1 unresolved discussion, LGTM missing from assignees mitiguy,sherm1(platform), labeled "do not merge"

a discussion (no related file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

Working

After we have buy-in on the idea, I'll need to port Anzu vs the new deprecation.

I have the PR ready now.



multibody/tree/rigid_body.h line 740 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

So far, zero seems to be passing CI. I cleaned up the branch a bit more so that I can test projects beyond Drake. Still working.

Done. You were right, zero seems fine. I guess my worries were unfounded.

Copy link
Contributor

@mitiguy mitiguy 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 5 files at r5, 12 of 13 files at r6, 1 of 1 files at r7, all commit messages.
Reviewable status: 1 unresolved discussion, LGTM missing from assignee sherm1(platform), labeled "do not merge" (waiting on @jwnimmer-tri)

Copy link
Collaborator Author

@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 1 of 1 files at r7, all commit messages.
Reviewable status: 1 unresolved discussion, LGTM missing from assignee sherm1(platform), labeled "do not merge" (waiting on @jwnimmer-tri)

@jwnimmer-tri
Copy link
Collaborator Author

Reminder to @sherm1 this one is ready for your final look -- and then please assign on-call platform after that.

Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

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

Feature :lgtm: with one typo.
+@ggould-tri for platform review Tuesday per rotation, please

Reviewed 1 of 19 files at r3, 1 of 5 files at r5, 12 of 13 files at r6, 1 of 1 files at r7, all commit messages.
Reviewable status: 1 unresolved discussion, LGTM missing from assignee ggould-tri(platform), labeled "do not merge" (waiting on @jwnimmer-tri)


multibody/tree/spatial_inertia.h line 484 at r7 (raw file):

      "2024-10-01",
      "The default constructor is deprecated. If you really want NaNs, then "
      "call the SpatialInertia<T>::NaN() factory function. If you were were "

typo: were were -> were

Copy link
Collaborator Author

@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 4 of 4 files at r8, all commit messages.
Reviewable status: LGTM missing from assignee ggould-tri(platform), labeled "do not merge" (waiting on @jwnimmer-tri)

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: on the structure and design; I trust that dynamics is in or near sufficient agreement about the semantics.

Reviewed 30 of 49 files at r1, 14 of 19 files at r3, 2 of 2 files at r4, 1 of 5 files at r5, 9 of 13 files at r6, 4 of 4 files at r8, all commit messages.
Reviewable status: 1 unresolved discussion, labeled "do not merge" (waiting on @jwnimmer-tri)

a discussion (no related file):
BTW: I don't know the current state of simulation behaviour when you Step() a simulation in the presence of zero-mass bodies; I know that it used to be aggressively nonlocal and baffling. If that's still true, this defaulting may make default-case error behaviour worse, in which case there should be an issue to improve the error behaviour.

(ref #19981 (comment) )


Copy link
Collaborator Author

@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: labeled "do not merge" (waiting on @jwnimmer-tri)

a discussion (no related file):

Previously, ggould-tri wrote…

BTW: I don't know the current state of simulation behaviour when you Step() a simulation in the presence of zero-mass bodies; I know that it used to be aggressively nonlocal and baffling. If that's still true, this defaulting may make default-case error behaviour worse, in which case there should be an issue to improve the error behaviour.

(ref #19981 (comment) )

I had the same worry, and did a lot of testing (both in CI and manually) to check, and wasn't able to find anything. If we experience user complaints, we can file issues with the specific compliant and work it from there.

Another thing that helped satisfy me with this approach is that URDF inertia defaults to zero, so we already need to be able to give good diagnostics about zeros, so this API can lean on the same diagnostic.


Deprecate the SpatialInertia default constructor.
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.

Reviewed 1 of 1 files at r9, all commit messages.
Reviewable status: :shipit: complete! all discussions resolved, LGTM from assignees ggould-tri(platform),mitiguy,sherm1(platform)

@jwnimmer-tri jwnimmer-tri merged commit 8658303 into RobotLocomotion:master Apr 2, 2024
10 checks passed
@jwnimmer-tri jwnimmer-tri deleted the naan branch April 2, 2024 18:46
@sherm1 sherm1 added the release notes: feature This pull request contains a new feature label Apr 11, 2024
RussTedrake pushed a commit to RussTedrake/drake that referenced this pull request Dec 15, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
release notes: feature This pull request contains a new feature release notes: fix This pull request contains fixes (no new features) release notes: newly deprecated This pull request contains new deprecations
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants