RobotLocomotion / drake

Model-based design and verification for robotics.
https://drake.mit.edu
Other
3.24k stars 1.25k forks source link

Provide warnings and/or errors for preposterous mass properties #20730

Open rpoyner-tri opened 8 months ago

rpoyner-tri commented 8 months ago

Is your feature request related to a problem? Please describe. When building models and scenes, there are a variety of common errors that lead to objects with ridiculous {mass, density, inertia, (maybe size)} that are difficult to debug only visually (say, with model_visualizer). Drake code (perhaps in multiple places?) should check for outlandish results and provide some user feedback.

Errors can arise from lack of documented units in data files, from typos, from scaling applied to some parts of a model and not others, etc.

For one example from Russ' students, see discussion here: https://drakedevelopers.slack.com/archives/C2WBPQDB7/p1699551031597909

Describe the solution you'd like Consider the various tools and APIs in the workflow of building and using models; provide early and detailed feedback about objects with mass properties that seem accidental.

In addition, consider documenting some best practices for debugging models.

Describe alternatives you've considered

Additional context Possible places to instrument:

jwnimmer-tri commented 8 months ago

So far, our parser warnings have been reserved for cases that need not halt the program, but where something is surely a mistake -- i.e., there are no false positives.

When adding warnings for conditions that might experience false positives, we might need to be more careful. Cases like "what you claimed was a rigid body is actually a black hole" seem pretty safe (no false positives), but depending on the thresholds you choose, maybe there could be spurious reports. If we open the door to false positive warnings during parsing, then we'll also need to consider how the user can suppress the warnings when they were false.

(This is less relevant for GUI tools like model_visualizer. I'm specifically talking about class Parser or class Simulator having false positives.)

jwnimmer-tri commented 7 months ago

Another example: https://stackoverflow.com/questions/77835087/drake-rotation-of-objects-appears-to-be-locked-even-though-i-did

It had an Izz of 5e13. I imagine that would trip the proposed "is a black hole" limit?

<?xml version='1.0'?>
<sdf xmlns:drake="http://drake.mit.edu" version="1.8">
  <model name='Box_0_5_0_5_0_5'>
    <link name='Box_0_5_0_5_0_5'>
      <inertial>
        <pose>2.25 0 3.75 0 0 0</pose>
        <mass>12.5</mass>
        <inertia>
          <ixx>1</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>1</iyy>
          <iyz>0</iyz>
          <izz>5208333333333336.0</izz>
        </inertia>
      </inertial>
      <visual name='visual'>
        <pose>2 -0.25 4 0 0 0</pose>
        <geometry>
          <mesh>
            <uri>Box_0_5_0_5_0_5.obj</uri>
            <scale>0.001 0.001 0.001</scale>
            <drake:declare_convex/>
          </mesh>
        </geometry>
      </visual>
...
mitiguy commented 7 months ago

@rpoyner-tri I agree. In the proper context (e.g., in dynamics analysis, but perhaps not for a kinematics analysis) it could be very helpful to proactively inform users when a body's mass properties (mass, center of mass, inertia) are invalid, preposterous, or mismatched with their given geometry. This was a hot topic this week with @SeanCurtis-TRI, @sherm1, and @DamrongGuoy. If it makes sense, I would enjoy working with you to help resolve parts of this. I put this as a topic for conversation for this upcoming Monday's Dynamics meeting. Blue sky: I wonder if it worthwhile to to consider a proactive message system (many details to resolve).

A few observations about the inertia given in the previous example and on Stack Exchange.

  1. Inertia properties in the example above are physically impossible (invalid) as they violate the "moment of inertia triangle inequality", i.e., izz <= ixx + iyy.

  2. With m = 12.5 kg and the values reported below copied from Stack Exchange -- also in Slack/on-ramp) the minimum sized bounding box would have length, width, depth dimensions of ≈ 9129 km, (70% of an Earth diameter)!

    <inertia>
    <ixx>5208333333333336.0</ixx>
    <ixy>-0.9094947017729282</ixy>
    <ixz>-0.9094947017729282</ixz>
    <iyy>5208333333333336.0</iyy>
    <iyz>-0.9094947017729282</iyz>
    <izz>5208333333333336.0</izz>
    </inertia>
  3. If the body's geometry is available (e.g., as collision geometry or perhaps visual geometry), the minimum bounding box dimensions can be compared to a bounding box afforded from the body's geometry. If the body's geometry bounding box is smaller than the minimum bounding box dimensions, then we can say definitely state that the given geometry cannot possibly generate the associated mass properties. In that case, the given geometry is too small for the given mass properties.

  4. In that Stack Exchange, Michael Zheng says "I just had to make the inertia a reasonable number (changed it to 0.5 * identity matrix, since the box is 0.5 x 0.5 x 0.5 m)". It is worth noting that for a 1 kg object, the minimum sized box is 1 x 1 x 1 meter. Since the mass was 12.5 kg, the minimum sized box is ≈ 0.28 x 0.28 x 0.28 meters (which means it is OK).

jwnimmer-tri commented 7 months ago

If the body's geometry is available (e.g., as collision geometry or perhaps visual geometry), the minimum bounding box dimensions can be compared to a bounding box afforded from the body's geometry.

There is no justification to believe that any or all of the proximity geometry, illustration geometry, or perception geometry associated with a body is strictly related to its inertia. If we yell at the user when their geometry shape(s) do not match the inertia, we will have false positives.

For the two examples of user mistakes upthread, I imagine we can easily diagnose those without bothering with the geometry. Is there any reason to believe a geometry-agnostic approach would be insufficient?

mitiguy commented 7 months ago

@jwnimmer-tri I like that is would be immediately useful to identify preposterous mass properties. It seems reasonable to first embark in that direction.

Also, we agree that known geometry does not have to match a body's inertia -- part of a recent conversation with @SeanCurtis-TRI. Interesting, Sean used the same "yell" language, when I would say, perhaps our goal would be to "inform" when the known geometry (e.g., collision geometry) can not physically match the body's inertia properties. This is meant to be a statement of fact that could be frequently helpful, particularly when the mismatch of known geometry and inertia properties are significant, possibly pointing to a units conversion problem.

jwnimmer-tri commented 7 months ago

... perhaps our goal would be to "inform" ...

Imagine a user whose robot.urdf for whatever reason has too-small geometry for some link that has inertia. (Maybe they shrunk some of the arm's geometry in order to make collision-free motion planning more tractable.) Now every single time they ever do anything with that robot, they will be "informed" that the geometry is small.

That kind of message clutter is actively harmful. Users hate it. I hate it. It masks other real messages that are more important. So yes, "your inertia doesn't fit in your geometry" is factually accurate, but it is clutter in this case because the message is a false positive intended to help diagnose a problem that isn't actually happening in that case.

If we can solve the problems that are actually in evidence (adding astrophysically massive bodies into MultibodyPlant) without dealing with geometry shapes, then investing our precious staff time into shape-related things seems like poor tradeoff to me.

sherm1 commented 7 months ago

If we do this at all, I think a nicer approach would be to have a standalone utility one could run voluntarily on a urdf to get some information about possible problems. (I'm imagining that most users wouldn't run this unless they had already encountered problems.) The penalty for nags and false positives in that case is much less.

jwnimmer-tri commented 7 months ago

For the case of detecting astrophysically massive bodies, I don't agree. Unless we have this particular diagnostic as part of the default workflow, nobody will think to run some separate tool when their objects are hovering instead of falling. Did the two users who struggled with this ever try running some other tool? On the margin, having model_visualizer give some extra reports might help for other categories of problems, but the median user setting up a simulation only ever runs class Parser and no other tools.

sherm1 commented 7 months ago

Agreed, but I think we can detect black holes without false positives so that could be normal workflow. But for heuristic geometry-vs-inertia checks (if we do them) I'd like to see a separate utility.

jwnimmer-tri commented 7 months ago

But for heuristic geometry-vs-inertia checks (if we do them) I'd like to see a separate utility.

Aha! The "this" in your "do this at all" was referring to the geometry-aware comparison, not the astrophysics. I misunderstood, but it's clear now in retrospect, thanks!


It seems like we're all in agreement -- for the problem of "warnings for ... preposterous mass properties" we can do something simple today (no geometry), call it done, and close this issue.

If we later encounter examples where a more nuanced tool would have helped a user, we can open a different issue to nominate that work.

mitiguy commented 6 months ago

Proposed action: An exception will be thrown if a rigid body that is not welded to ground has a spatial inertia that corresponds to a preposterously large physical object.

From discussion: Consider only checking a spatial inertia's physical extents if the spatial inertia is used for a dynamic analyses. (e.g., skip the check if the body is welded to the world, is only used for kinematic analysis or collision queries, etc.).

Note: A spatial inertia that is associated with a preposterously large object can arise from a simple units conversion error that can enter Drake directly from C++ or Python or from an erroneous URDF, SDF, or USD file. For example, a copy/paste from a CAD/CAE tool of 60 (which for CAD/CAE convenience may use units of gcm²) into Drake or a SDF file which assumes units of kgm², causes a 10⁷ error conversion!

sherm1 commented 6 months ago

To be clear, the proposal on the table is

For the above heuristic, the check must be performed in MultibodyPlant::Finalize() because we can't know who is welded to whom until then. Note that this proposal will reject preposterous-inertia bodies even if the user is only going to do kinematics with the model.

*preposterous == object with that inertia would have to be at least 500m on a side

We are looking for input on

jwnimmer-tri commented 6 months ago

Assuming that the inertia is well-formed (but possibly very large), then any heuristic that throws an exception (i.e., actively prevents) a motion planning problem from computing its answer is unsuitable. Users who perform motion planning should never need to worry about the inertia of their terrain, for example. That's true even if the terrain offsets are adjusted using unactuated joints instead of offset welds.

sherm1 commented 6 months ago

We could add a config flag on MbP to disable the check. But motion planners would have to set that explicitly if they care (the "preposterous inertia" error message could suggest that). Would that be sufficient and innocuous enough that the check would still be a net positive? I'm guessing that it would be a rare occurrence (since it requires a very large terrain).

jwnimmer-tri commented 6 months ago

What is a reasonable size for defining "preposterous" for robot applications?

In the two examples of user mistakes in evidence so far, please explain precisely what is the most generous (i.e., largest) limit that would have identified them? Asking "how tight can we go without bothering anyone" is the wrong question -- it risks disaster with no real upside. If the things we need to flag are all like 10^12 or whatever, why do we care about whether robots need 10^3 vs 10^4? The right question to ask is "what's the most generous limit that would catch the mistakes we know actually happen"?

jwnimmer-tri commented 6 months ago

Would that be sufficient and innocuous enough that the check would still be a net positive?

It's a question of false positive / true positive / false negative / true negative rate. In other words, I can't answer until you explain whether you're trying to fine-tune the limit to be aircraft carriers and the empire state building versus robots inside a room, or whether you're only trying to isolate planets (which warp earth-calibrated gravity) versus non-planets (which don't).

If the only thing you're planning to throw exceptions on is planets, then we can be a lot more accepting of some hurdles when trying to do kinematics, since people trying to motion-plan orbits using MultibodyPlant would be a pretty rare use case.

mitiguy commented 6 months ago

Proposed action (version 2): An exception will be thrown if a rigid body that is not welded to ground has a spatial inertia that corresponds to a preposterously large physical object. If the maximum spatial extents dₘₐₓ of a rigid body can be assessed another way (e.g., the spatial diagonal of the bounding box from collision geometry or visual geometry, etc.), dₘₐₓ is used to inform preposterous, e.g., preposterous = max(10 * dₘₐₓ, 500 meters). If no geometry information is available dₘₐₓ=0. TBD -- how difficult it is to get dₘₐₓ (brief conversation with Sean earlier).

jwnimmer-tri commented 6 months ago

Please trust me that geometry cannot be part of the heuristic. I already explained this upthread.

sherm1 commented 6 months ago

Paul's idea was to use that to deal with the specific use case you brought up: a giant terrain object. Wouldn't that always be expected to include a giant piece of geometry? IIUC the test would go like this:

If that is reasonably implementable, I think it addresses all the use cases that have been mentioned so far upthread,.

jwnimmer-tri commented 6 months ago

In the two examples of user mistakes in evidence so far, please explain precisely what is the most generous (i.e., largest) limit that would have identified them.

mitiguy commented 6 months ago

Example 1: With m = 12.5 kg and the values reported below copied from Stack Exchange -- also in Slack/on-ramp) the minimum sized bounding box would have length, width, depth dimensions of ≈ 9129 km, (70% of an Earth diameter) and the spatial diagonal is 15,812 km (123% of an Earth diameter).

Example 2: I do not have data (assuming it is here).

jwnimmer-tri commented 6 months ago

The other example was:

... a mug was falling through the table ... the root cause was that the obj was specified in mm... [the user] did mesh_to_model, but then set the scale on the visual and collision meshes manually. The density was 1000^3 times larger than it should have been. That's 10^12 kg/m^3 ...

Is that enough to provide a guesstimate?

If not, we'll ask for more specific numbers from the user.

(If the diameter would be more than 15,000 km, we can set it aside and focus on the other example.)

mitiguy commented 6 months ago

I cannot provide an estimate with the information provided. The following data would be helpful: the body's mass and inertia matrix for the center of mass (or 3 moments and 3 products of inertia). Alternatively, the body's mass, inertia matrix for another point, and the position vector from that point to the center of mass. Need to head to a meeting, will continue tomorrow.

jwnimmer-tri commented 6 months ago

Would it suffice to take one of the sample mug meshes we have lying around, mis-scale it by 1000x, plug into mesh_to_model, and then use those numbers? It surely wouldn't be the exact numbers the user was trying, but mugs aren't that different from each other, are they? It seems to me like we'd still be within an order of magnitude, and able to move forward here without waiting on the user.

jwnimmer-tri commented 6 months ago

Sorry, I think I made a leadership error here and have been missing the forest for the trees. When we started talking about heuristics, I didn't push strongly enough to revisit the requirements as captured in the issue.

Both users who were bitten used mesh_to_model, an automation tool that had a hazard of emitting preposterous inertia values. Rico already implemented #20966 to solve that hazard. As I understand it, that fix probably resolves both reports of user's struggles -- pending confirmation that the volume limits added in #20966 would have flagged these two particular mesh files, there is no further work required to address those two particular problems.

So -- we had a problem where an automation tool we provided spit out preposterous numbers, but it wasn't sufficiently cautious of that hazard, and users did not notice the bad numbers when skimming their file. Now that the mesh_to_model tool is fixed, it is doubtful whether there is much (if any) further work here that's worth doing.

The remaining question is -- do we have any other automated tools that produce preposterous inertia? The only one I can think of would be detail_mesh_parser.h. It should probably have a diagnostic.Warning that's identical to #20966, so that users will quickly notice in case they are using the wrong scale. The warning should point users to mesh_to_model in order to control the scale.

So to me, the only remaining call to action here is to consider copying the obj-scale warning logic from mesh_to_model into detail_mesh_parser. Since that's a "every time you load" warning instead of a "one-time conversion warning" we might want to be slightly more cautious with warning spam, but it's a fair question to pursue.

I don't see any reason for MbP to try to do anything new here. We don't have any problem reports that support flagging large inertia at that layer. We have plenty of other more useful work we could be doing, instead.