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

Improve exception message for bad geometry in .obj file. #21929

Open
wants to merge 17 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 16 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions geometry/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -808,6 +808,9 @@ filegroup(
name = "test_obj_files",
testonly = 1,
srcs = [
"test/bad_geometry_corrected.obj",
"test/bad_geometry_volume_negative.obj",
"test/bad_geometry_volume_zero.obj",
"test/convex.obj",
"test/cube_corners.obj",
"test/cube_with_hole.obj",
Expand Down
26 changes: 26 additions & 0 deletions geometry/test/bad_geometry_corrected.obj
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
# File: bad_geometry_corrected.obj
# The geometry in this file produces valid mass and inertia properties
# due to proper winding (order of the vertices) in all of its faces.
# This file has the same vertices as the file bad_geometry_volume_zero.obj.
# However this file's faces were ordered to produce a valid mesh with a
# positive volume (volume = +0.5) and a valid centroid and spatial inertia.
# Related: issue #21924 [github.com/RobotLocomotion/drake/issues/21924].
# ------------------------------------------------------------------------------

# 6 vertices.
v 0.0 0.0 0.5
v 0.0 0.0 -0.5
v 0.0 1.0 0.5
v 0.0 1.0 -0.5
v 1.0 0.0 0.5
v 1.0 0.0 -0.5

# 8 faces.
f 1 5 3
f 2 4 6
f 1 3 2
f 2 3 4
f 3 5 4
f 4 5 6
f 5 1 6
f 6 1 2
22 changes: 22 additions & 0 deletions geometry/test/bad_geometry_volume_negative.obj
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
# File: bad_geometry_volume_negative.obj
# The geometry in this file does not describe a closed triangular mesh (it only
# has ONE face) and Drake's mass properties calculator produces an invalid
# volume, invalid mass, invalid center of mass, and invalid inertia matrix.
# An additional defect (which makes invalidity easier to detect) is that its one
# face has a winding (order of its vertices) that results in Drake calculating
# a negative volume for this mesh (volume = -1.0).
# Related files: bad_geometry_volume_zero.obj and bad_geometry_corrected.obj
# Related: issue #21924 [github.com/RobotLocomotion/drake/issues/21924].
# ------------------------------------------------------------------------------

# The 3 vertices below together with the origin (0, 0, 0) form a tetrahedron.
# Drake happens to use this single tetrahedron to calculate volume and other
# mass proeprties. However, this mesh only has ONE face, so its bounding box
# indicates a volume = 0, which is another way to detect mesh defects.
v 1.0 0.0 0.0
v 1.0 2.0 0.0
v 1.0 0.0 3.0

# This mesh's single face has a bad winding (normal points inward, not outward).
f 3 2 1

31 changes: 31 additions & 0 deletions geometry/test/bad_geometry_volume_zero.obj
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
# File: bad_geometry_volume_zero.obj
# The geometry in this file produces invalid mass and inertia properties
# due to improper winding (order of the vertices) in some of its faces.
# This file has the same vertices as the file bad_geometry_corrected.obj.
# However this file's faces have disordered vertices which produce a mesh
# with zero volume (volume = 0) and an invalid centroid and spatial inertia.
# ------------------------------------------------------------------------------
# This file uses the data in the original bad mesh file submitted by the Drake
# user in issue #21924 [github.com/RobotLocomotion/drake/issues/21924]. This
# issue was resolved in PR #21929 [github.com/RobotLocomotion/drake/pull/21929]
# by creating a more coherent error message when the volume calculated from
# geometry in an .obj file is not reasonably positive.
# ------------------------------------------------------------------------------

# 6 vertices.
v 0.0 0.0 0.5
v 0.0 0.0 -0.5
v 0.0 1.0 0.5
v 0.0 1.0 -0.5
v 1.0 0.0 0.5
v 1.0 0.0 -0.5

# 8 faces.
f 1 3 5
f 2 4 6
f 1 2 3
f 2 3 4
f 3 4 5
f 4 5 6
f 5 6 1
f 6 1 2
1 change: 1 addition & 0 deletions multibody/parsing/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -529,6 +529,7 @@ drake_cc_googletest(
name = "parser_test",
data = [
":test_models",
"//geometry:test_obj_files",
"//multibody/benchmarks/acrobot:models",
"@drake_models//:iiwa_description",
] + _DM_CONTROL_MUJOCO_FILES,
Expand Down
16 changes: 16 additions & 0 deletions multibody/parsing/test/parser_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -441,6 +441,22 @@ GTEST_TEST(FileParserTest, InterleavedRenaming) {
EXPECT_EQ(parser.GetCollisionFilterGroups(), expected);
}

// Ensure an exception is thrown if parsing a mesh with zero volume.
// Related: issue #21924 [github.com/RobotLocomotion/drake/issues/21924].
GTEST_TEST(FileParserTest, ZeroVolumeShouldThrowException) {
systems::DiagramBuilder<double> builder;
AddMultibodyPlantSceneGraphResult<double> plant_and_scene_graph =
AddMultibodyPlantSceneGraph(&builder, /* time_step = */ 0.0);
MultibodyPlant<double>& plant = plant_and_scene_graph.plant;
Parser parser(&plant);
std::string filename = "drake/geometry/test/bad_geometry_volume_zero.obj";
std::string geometry_file_path = FindResourceOrThrow(filename);
DRAKE_EXPECT_THROWS_MESSAGE(
parser.AddModels(geometry_file_path),
".*volume of a triangle surface mesh is.* whereas a reasonable "
"positive value of .* was expected. The mesh may have bad geometry.*");
}

} // namespace
} // namespace multibody
} // namespace drake
35 changes: 35 additions & 0 deletions multibody/tree/geometry_spatial_inertia.cc
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,41 @@ SpatialInertia<double> CalcSpatialInertia(
}

const double volume = vol_times_six / 6.0;
// A valid mesh should have an inherently positive volume.
// Throw an exception if volume is negative or nearly zero. This test of
// "reasonably positive" volume is more stringent than the mass ≥ 0 test in
// SpatialInertia::IsPhysicallyValid(). Reminder: The volume of a mesh can be
// calculated (and should be positive) whereas spatial inertia does not deal
// with volume. Instead, spatial inertia deals with mass, including idealized
// zero volume massive objects such as particles, rods, and plates.
// Note: If we omit throwing an exception for negative or zero volume, a
// different exception would still be otherwise thrown in code called by the
// spatial inertia constructor below and this function still fails to return.
// For negative volume, the associated less-helpful spatial inertia exception
// message would be e.g., "mass = -0.5 is not positive and finite.", whereas a
// zero volume creates a divide-by-zero in two places below and the associated
// obscure exception message would be "Unable to calculate the eigenvalues or
// eigenvectors of the 3x3 matrix associated with a RotationalInertia.".
// Related: issue #21924 [github.com/RobotLocomotion/drake/issues/21924].
constexpr double kEpsilon = 1.0E-14; // ≈ 64*numeric_limits<double>::epsilon
if (volume <= kEpsilon) {
// TODO(Mitiguy) Consider changing the function signature to add an optional
// mesh_name argument (e.g., mesh_name = someFilename.obj) and using
// mesh_name in the following error_message. For a simulation involving
// many meshes, this helps quickly identify an offending mesh.
// TODO(Mitiguy) Sean Curtis thought the following error message may not be
// enough guidance, so he suggested adding a hyperlink in error_message to
// https://drake.mit.edu/troubleshooting.html for a proper treatment of
// the issue (ideally with Sean's input/expertise).
const std::string error_message = fmt::format(
"{}(): The calculated volume of a triangle surface mesh is {} whereas "
"a reasonable positive value of at least {} was expected. The mesh may "
"have bad geometry, e.g., it is an open mesh or the winding (order of "
"vertices) of at least one face does not produce an outward normal.",
__func__, volume, kEpsilon);
throw std::logic_error(error_message);
}

const double mass = density * volume;
const Vector3d p_GoGcm = accum_com / (vol_times_six * 4);
// We can compute I = C.trace * 1₃ - C. Two key points:
Expand Down
9 changes: 6 additions & 3 deletions multibody/tree/geometry_spatial_inertia.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,12 +42,15 @@ SpatialInertia<double> CalcSpatialInertia(const geometry::Shape& shape,
certain requirements:

- The mesh must *fully* enclose a volume (no cracks, no open manifolds,
etc.)
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.
We do not perform the expensive checks that the mesh meets these requirements.
Instead we compute the volume enclosed by the mesh, and if the volume is zero
or negative we'll throw an exception. In other cases we won't notice unmet
requirements and the returned SpatialInertia may be meaningless.
@throws std::exception if the volume of `mesh` is negative or nearly zero.
@pydrake_mkdoc_identifier{mesh} */
SpatialInertia<double> CalcSpatialInertia(
const geometry::TriangleSurfaceMesh<double>& mesh, double density);
Expand Down
36 changes: 36 additions & 0 deletions multibody/tree/test/geometry_spatial_inertia_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -159,6 +159,42 @@ GTEST_TEST(GeometrySpatialInertiaTest, Convex) {
/* tolerance = */ 1e-1));
}

// Throw an exception message when CalcSpatialInertia(Shape) calculates an
// invalid volume for an associated geometry file.
GTEST_TEST(GeometrySpatialInertiaTest, ExceptionOnBadGeometry) {
// Throw an exception for the mesh in bad_geometry_volume_negative.obj since
// its calculated volume is negative (volume = -1.0).
std::string filename = "drake/geometry/test/bad_geometry_volume_negative.obj";
std::string geometry_file_path = FindResourceOrThrow(filename);
const geometry::Mesh bad_geometry_volume_negative(geometry_file_path, 1.0);
DRAKE_EXPECT_THROWS_MESSAGE(
CalcSpatialInertia(bad_geometry_volume_negative, kDensity),
".*volume of a triangle surface mesh is.* whereas a reasonable "
"positive value of .* was expected. The mesh may have bad geometry.*");

// Throw an exception for the mesh in bad_geometry_volume_zero.obj since
// its calculated volume is zero (volume = 0).
// This file has the same vertices as bad_geometry_corrected.obj (below),
// but some of this file's faces have disordered vertices which produce a mesh
// with zero volume (volume = 0) and invalid centroid and spatial inertia.
filename = "drake/geometry/test/bad_geometry_volume_zero.obj";
geometry_file_path = FindResourceOrThrow(filename);
const geometry::Mesh bad_geometry_volume_zero(geometry_file_path, 1.0);
DRAKE_EXPECT_THROWS_MESSAGE(
CalcSpatialInertia(bad_geometry_volume_zero, kDensity),
".*volume of a triangle surface mesh is.* whereas a reasonable "
"positive value of .* was expected. The mesh may have bad geometry.*");

// Ensure no exception is thrown for the mesh in bad_geometry_corrected.obj.
// This file has the same vertices as bad_geometry_volume_zero.obj (above),
// but this file's faces have vertices in proper order. Hence, this mesh has
// a positive volume (volume = +0.5) and appropriate spatial inertia.
filename = "drake/geometry/test/bad_geometry_corrected.obj";
geometry_file_path = FindResourceOrThrow(filename);
const geometry::Mesh ok_geometry_obj(geometry_file_path, 1.0);
EXPECT_NO_THROW(CalcSpatialInertia(ok_geometry_obj, kDensity));
}

// Exercises the common code paths for Mesh and Convex (i.e., "MeshTypes").
template <typename MeshType>
class MeshTypeSpatialInertaTest : public testing::Test {};
Expand Down