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

CalcSpatialInertia fails on this Hello Robot obj #21666

Open
RussTedrake opened this issue Jul 2, 2024 · 23 comments
Open

CalcSpatialInertia fails on this Hello Robot obj #21666

RussTedrake opened this issue Jul 2, 2024 · 23 comments
Assignees
Labels

Comments

@RussTedrake
Copy link
Contributor

RussTedrake commented Jul 2, 2024

What happened?

Following #20444, I've put a simple failure reproduction here: 2fe7f24

This attempts to compute the spatial inertia from the hello robot model in mujoco menagerie but fails with

Expected: CalcSpatialInertia(unit_scale_obj, kDensity) doesn't throw an exception.
  Actual: it throws std::runtime_error with description "Spatial inertia fails SpatialInertia::IsPhysicallyValid().
 mass = 2.1647959683444456e-05
 Center of mass = [-0.24465954725602354  -3.041901842037344e-06  0.02583678929053868]
 Inertia about point P, I_BP =
[1.90172e-08  -1.2568e-11  1.35882e-07]
[-1.2568e-11  1.30846e-06  1.45236e-12]
[1.35882e-07  1.45236e-12   1.2914e-06]
 Inertia about center of mass, I_BBcm =
[ 4.56633e-09   3.54305e-12  -9.59847e-10]
[ 3.54305e-12  -1.79939e-09  -2.49019e-13]
[-9.59847e-10  -2.49019e-13  -4.40846e-09]
 Principal moments of inertia about Bcm (center of mass) =
[-4.509963383944518e-09  -1.799395202505969e-09  4.667840740414944e-09]

Additionally the CalcSpatialInertia doc strings do not actually declare that they could throw an exception for this reason.

Version

No response

What operating system are you using?

Ubuntu 22.04

What installation option are you using?

compiled from source code using Bazel

Relevant log output

No response

@jwnimmer-tri
Copy link
Collaborator

jwnimmer-tri commented Jul 2, 2024

The CalcSpatialInertia(mesh=, ...) API documents that:

The mesh must fully enclose a volume (no cracks, no open manifolds, etc.). All triangles must be "wound" such that their normals point outward (according to the right-hand rule based on vertex winding). If these requirements are not met, a value will be returned, but its value is meaningless.

I'm guessing that the obj file in question might not meet those conditions.

So there are at least three problems:

(1) Instead of returning a "meaningless" value like it promised, sometimes CalcSpatialInertia(mesh=...) throws.

(2) The docs for the related overload CalcSpatialInertia(shape=...) fail to repeat the caveats from the more specific overload that it delegates to.

(3) Our parser(s?) call CalcSpatialInertia(shape=...) without sufficient regard to whether or not the preconditions for mesh sensibility have been meet. Allowing the "meaningless" value to flow through the parse would be fine, but at least the parser needs to warn the user about that case when encountered -- so it can't be completely ignorant of the circumstance.

Or, if this particular obj file actually meets those requirements, then we have even more going wrong beyond those points.

On first impression, the ideal fix would be to update the contract of CalcSpatialInertia(...) to always produce a valid answer -- no more "meaningless". If we can't do that, then instead we need to provide an overload with a structured error channel, and wire the errors up to the parser. This could be as simple as making the return value optional<> and returning null when the result cannot be computed.

In the meantime, possibly we should hotfix the function to at least never throw.

@RussTedrake
Copy link
Contributor Author

Thanks Jeremy. I completely agree, and would note that
(1) checking properly that the mesh satisfies those conditions in the parser directly would be impractical without a geometry helper method.
(2) mujoco parses these files ok (and must calculate some inertia). We could look at what they do.

I think propagating the error condition properly up through the parser (without a throw) would be better than nothing. Removing the apparently overly conservative requirements would of course be better. As a fallback, I could imagine CalcSpatialInertia could try to compute the inertia and if it is not physically valid, then it could fall back to a simpler approximation (like taking the volume of the convex hull, or even obb), so that it always returns something valid.

@SeanCurtis-TRI
Copy link
Contributor

Several thoughts:

Model compliance

The model you've referenced does indeed have arbitrary open faces (they are the red faces you can see):
image

It looks like it's appropriate for visualization, but not for proximity or physics. I'm curious what mujoco actually does with meshes of that type. We could certainly compute a spatial inertia assuming the mass were strictly distributed on the surface of the triangles. In that case, we wouldn't be dependent on closed manifolds or consistent winding.

Calculating spatial inertia

The primary problem with computing spatial inertia from an obj is there are many ways to produce a "meaningless" but apparently otherwise valid spatial inertia. In this case, it just turns out the non-compliance is sufficient to push the resulting tensor out of "meaningless" and into "non-physical".

Today, we can easily detect the non-physical tensors (which is what happens here belatedly), but we can't generally detect meaningless tensors. So, any change to the API and the promises cannot eliminate the fact that if you invalidate assumptions about the obj, you may get something back meaningless. Still, this would be the "sometimes it throws".

Alternatively, we could change to a different computation mechanism that would be less sensitive to those issues (the aforementioned "mass on surface" approach). I don't have any intuition of how that might mess with the physics -- how different that is from an assumption of uniform density for the enclosed space.

@SeanCurtis-TRI
Copy link
Contributor

P.S. Geometric analysis is still currently beyond Drake's capacity. But it's been on my wish list for years.

@jwnimmer-tri
Copy link
Collaborator

As a point of reference, one of the ways that SDFormat specifies handling auto inertia for non-convex meshes is to convert the mesh into a voxelized approximation, and sum the inertia of the voxels.

@RussTedrake
Copy link
Contributor Author

I think we already support non-convex. It's not clear that would work for open faces.

@jwnimmer-tri
Copy link
Collaborator

Well, I was trying to talk about what to do with non-convex meshes that we currently mis-process (not non-convex meshes overall), but anyway that was getting off the point. Sean had a better question..

I'm curious what mujoco actually does ...

This is the only question that matters.

We are writing a parser for the mujoco file format. The only question that matters is what is specified to happen, by the file format documentation, when auto-inertia is being used on an open mesh. Our job is to implement that specification.

If the specification doesn't say, they we ask upstream to clarify it, and in the meantime we can guess what the spec would say by reading the mujoco parsing code and seeing what happens in their first-party parser.

My attempts to reason about this bottom-up from CalcSpatialInertia were missing the forest for the trees. Yes, the function is badly-shaped, and yes we're not calling it properly, but we need to work the problem top-down. What math does the specification command, then therefore what should our code look like.

@SeanCurtis-TRI
Copy link
Contributor

To be clear - non-convexity is not an issue here. Non-convexity doesn't cause problems at all. Open meshes do.

Agreed - we need to find out what mujoco is doing. 100% on board with that.

@jwnimmer-tri
Copy link
Collaborator

I was treating the Convex shape as a special case because computing its uniform-density inertia should always be easy and correct, even if some triangles are missing or wound the wrong way or etc. One we take the hull, the inertia should be easy.

Probably a moot point for this thread though, since I don't think the drake:declare_convex marker is part of our mjcf parser in the first place, so there are never any Convex shapes anyway.

@jwnimmer-tri jwnimmer-tri added the component: multibody parsing Loading models into MultibodyPlant label Jul 2, 2024
@SeanCurtis-TRI
Copy link
Contributor

BTW Mujoco explicitly has a parameter called "shellinertia" indicating whether the mass is distributed on the surface. Its default value is false.

Also, there's a compiler option, exactmeshinertia that defaults to false, but when true, emphasizes that the inertia is exact for "any closed mesh geometry" (emphasis mine).

So, having done a quick pass through the documentation, I didn't see enough information vis a vis computing the spatial inertia from a mesh. I'd invite others to see if they can find it, but I suspect we'll have to turn to the code/developers to find out.

@RussTedrake
Copy link
Contributor Author

RussTedrake commented Jul 3, 2024

The mujoco ComputeVolume() code for a mesh appears to be here: https://github.com/google-deepmind/mujoco/blob/df7ea3ed3350164d0f111c12870e46bc59439a96/src/user/user_mesh.cc#L1214 . I agree that they aren't doing anything fancy there.

@RussTedrake
Copy link
Contributor Author

My current mental model is that mujoco is probably generating physically invalid inertias for those models, but then not doing the consistency check. But that should be verified.

@RussTedrake
Copy link
Contributor Author

in #21403, i've implemented the fallback of using the volume of the OBB if the CalcSpatialInertia fails. (with a TODO reminding me that we could do better by taking the volume of the convex hull).

@yuvaltassa
Copy link

My current mental model is that mujoco is probably generating physically invalid inertias for those models, but then not doing the consistency check. But that should be verified.

I don't think invalid inertias are generated. If there is a specific question about inertia computation (which I agree needs work!), I'm happy to address.

@RussTedrake
Copy link
Contributor Author

Hi Yuval. Indeed, I see now here that you catch the negative volume case and use the convex hull if needed (I did the OBB to be quick, but using the convex hull as the fallback is now a to-do in our mujoco parser, too). And you do have the sanity check a bit below. Sorry for not looking more thoroughly!

@RussTedrake
Copy link
Contributor Author

RussTedrake commented Jul 6, 2024

BTW: My updated understanding is that our CalcSpatialInteria (and MuJoCo's comparable method), only declare failure -- and thus will fall back to a convex hull computation -- in the event of total failure (e.g. negative volume or nonphysical inertias). I suspect that if the mesh is not watertight or has some strange windings, then we can still be arbitrarily wrong (e.g. removing volume that should be added, but not passing the threshold into negative volume?)

I believe the algorithms work by taking a central point then iterating over surface triangles, computing the quat mesh volume/inertia. Without having studied it carefully, I believe that the intended behavior for this algorithm must be to sometimes compute negative volume/inertia for one step; this must be the reason that it works even for nonconvex meshes? So I don't know if there is an more narrow error condition that one could check, but it's worth keeping in mind.

@yuvaltassa
Copy link

Side note, here's roughly where MuJoCo stands WRT inertia computation.

At some point we added the exactmeshinertia compiler option, thinking that eventually the convex approximation business will be deprecated. However as Russ says, if your mesh is not correctly oriented and watertight this algorithm can give negative inertias (easy to catch) or arbitrarily wrong positive inertias (harder to catch). What's more, meshes in the wild are very rarely watertight and correctly oriented and importantly, users have no idea how to fix that. So the convex approximation has to stay.

A parallel bit of storyline is the surface inertia (<geom shellinertia> in MJCF). Surface inertia doesn't care about mesh goodness and always does the right thing (which is why we sometimes use it for bad/tiny meshes). The thing that got us stuck is that I really wanted to replace the binary surface/volume flag with a real-valued number that corresponds to shell thickness, either in units of length or [0...1] such that at 0 you get surface and at 1 you get uniform volume (that's what you'd want for e.g. a tennis ball). It's pretty easy to write this down for primitives, but I spent a week with meshes and could not find an analytic formula, even for convex ones (though I found some pretty good approximations!).

So our current plan is:

  1. Remove the exactmeshinertia compiler flag and move it into the <mesh> tag, defaulting to false. If the user knows that a specific mesh is good they can say that. If they know that all their meshes are good they can say that using mesh defaults.
  2. Surface inertia remains a binary flag in geoms, we still need to add the formulas for primitives (currently only meshes are supported).

@quagla did I forget anything?

If you guys have comments on the above plan, or if you can come up with the general formula for the inertia of a thick shell geom, let us know!

@nepfaff
Copy link
Member

nepfaff commented Jul 7, 2024

In the past, I used the ray stabbing method here for computing inertia for not watertight meshes (a cuda implementation exists here). This method allows you determine whether a point is inside or outside a mesh for non-watertight meshes (I did not test ambiguous situations). One can then sample points in the object's bounding box, filter the inside points, and treat them as point masses for computing inertia with a discrete approximation. I tested it on various shapes and got almost identical results to Drake and trimesh.

@SeanCurtis-TRI
Copy link
Contributor

@yuvaltassa has done a great job summarizing the challenges. It's one of the reason that Drake's documentation is tenuous: "Meet the requirements or don't be guaranteed on getting something physical." Nice to know the convex hull is the fallback -- that's something I'll add today so that we're playing the same game as mujoco.

@SeanCurtis-TRI
Copy link
Contributor

FYI #21693 will go ahead and finish replicating the mujoco logic -- using convex hull as the fallback. At that point, I believe we can close this.

@SeanCurtis-TRI
Copy link
Contributor

D'oh! I spoke too soon. While #21693 will go ahead and get Drake's observable behavior in line with mujoco, it still isn't doing it the "right way" -- throwing and catching exceptions. So, this should stay open to track that part of the issue.

@rpoyner-tri
Copy link
Contributor

FWIW, #21929 is motivating me to clean up the throwing from CalcSpatialInertia. Rather, I will work with that PR to offer some internal:: non-throwing alternative entry points.

@SeanCurtis-TRI
Copy link
Contributor

@yuvaltassa

I dug a bit more and the phrase, "So the convex approximation has to stay." has gained new signficance.

tl;dr Drake has implemented the "convex approximation" as the convex hull. Mujoco has not. Even though it prints a warning claiming the convex hull is being used, in fact, that is not the case.

In ComputeVolume() the request to not use the "exact" mesh inertia causes the volume of each computed tet to become positive. The sum of all of these volume magnitudes is not generally the volume of the convex hull. It is some value greater than or equal to the convex hull's volume.

The tetrahedra are calculated based on the centroid of all of the triangles (which is definitely contained within the convex hull of the mesh). However, if the mesh contains layers or voids between the surface of the convex hull and that centroid point, extra volume will be added in. Potentially a great deal of volume.

For example, imagine a spherical shell with outer radius R and inner radius r. The approach for computing the volume would essentially compute the volume of the sphere of radius R and subtract the volume of a sphere with radius r (based on the winding of triangle vertices implying surface normals in opposite directions). However, when exactmeshinertia is set to false, it actually computes the sum of the two volumes. In this example, that would be a volume of essentially double the volume of the convex hull (and this really is the upper limit for how far off it would be).

Is this a problem? Probably not a big one. Between the assumption of uniform density throughout the mesh, largely arbitrary density values, and the fact that even the exact convex hull is probably a poor approximation of the actual mesh, the mujoco volume computed here is not particularly more arbitrary than one computed on the convex hull.

If there is actually a problem it is that the center of mass of this convex approximation could be offset in a silly way. If the underlying mesh had a void inside of it (like a hole bored through it), the actual center of mass would be away from the void. The center of mass of the convex hull would be closer to the void, and the center of mass computed by this approach would bias the center of mass even closer to the void.

I'd still say that what Drake is doing is good, inspired by mujoco's warning. Using the convex hull as a fall back proxy is reasonable. But that doesn't mean Drake will produce the same spatial inertia as mujoco in when they both fall back.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

No branches or pull requests

6 participants