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 all 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 @@ -606,6 +606,7 @@ drake_cc_googletest(
name = "detail_mesh_parser_test",
data = [
":test_models",
"//geometry:test_obj_files",
"//geometry/render:test_models",
],
deps = [
Expand Down
7 changes: 6 additions & 1 deletion multibody/parsing/detail_mesh_parser.cc
Original file line number Diff line number Diff line change
Expand Up @@ -158,8 +158,13 @@ std::optional<ModelInstanceIndex> AddModelFromMesh(
const ModelInstanceIndex model_instance =
plant.AddModelInstance(model_instance_name);

const SpatialInertia<double> M_BBo_B = CalcSpatialInertia(
CalcSpatialInertiaResult result = DoCalcSpatialInertia(
*named_mesh.mesh, 1000.0 /* water density ≈ 1000 kg/m³ */);
if (std::holds_alternative<std::string>(result)) {
workspace.diagnostic.Error(std::get<std::string>(result));
return {};
}
const auto M_BBo_B = std::get<SpatialInertia<double>>(result);
const RigidBody<double>& body =
plant.AddRigidBody(candidate_name, model_instance, M_BBo_B);

Expand Down
24 changes: 17 additions & 7 deletions multibody/parsing/detail_mujoco_parser.cc
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ namespace drake {
namespace multibody {
namespace internal {

using drake::internal::DiagnosticPolicy;
using Eigen::Matrix3d;
using Eigen::Vector2d;
using Eigen::Vector3d;
Expand Down Expand Up @@ -480,9 +481,12 @@ class MujocoParser {
// up mesh inertias, it uses the mujoco geometry _name_ and not the
// mesh filename.
InertiaCalculator(
const DiagnosticPolicy& policy,
std::string name,
std::map<std::string, SpatialInertia<double>>* mesh_inertia)
: name_(std::move(name)), mesh_inertia_(mesh_inertia) {
: policy_(policy),
name_(std::move(name)),
mesh_inertia_(mesh_inertia) {
DRAKE_DEMAND(mesh_inertia != nullptr);
}

Expand Down Expand Up @@ -513,9 +517,11 @@ class MujocoParser {
if (mesh_inertia_->contains(name_)) {
M_GGo_G_unitDensity = mesh_inertia_->at(name_);
} else {
try { // TODO(21666), remove the try-catch.
M_GGo_G_unitDensity = CalcSpatialInertia(mesh, 1.0 /* density */);
} catch (const std::exception& e) {
CalcSpatialInertiaResult result =
DoCalcSpatialInertia(mesh, 1.0 /* density */);
if (std::holds_alternative<std::string>(result)) {
policy_.Warning(std::get<std::string>(result));

// As this calculator is only used for Mesh shapes that are specified
// in a mujoco file, the mesh *must* be on-disk.
DRAKE_DEMAND(mesh.source().is_path());
Expand All @@ -525,9 +531,11 @@ class MujocoParser {
geometry::Convex(mesh.source().path(), mesh.scale()),
1.0 /* density */);
used_convex_hull_fallback_ = true;
} else {
M_GGo_G_unitDensity = std::get<SpatialInertia<double>>(result);
}
mesh_inertia_->insert_or_assign(name_, M_GGo_G_unitDensity);
}
mesh_inertia_->insert_or_assign(name_, M_GGo_G_unitDensity);
}

void ImplementGeometry(const geometry::HalfSpace&, void*) final {
Expand All @@ -539,6 +547,7 @@ class MujocoParser {
}

private:
const DiagnosticPolicy& policy_;
std::string name_;
std::map<std::string, SpatialInertia<double>>* mesh_inertia_{nullptr};
bool used_convex_hull_fallback_{false};
Expand Down Expand Up @@ -879,7 +888,8 @@ class MujocoParser {
WarnUnsupportedAttribute(*node, "user");

if (compute_inertia) {
InertiaCalculator calculator(mesh, &mesh_inertia_);
auto policy = diagnostic_.MakePolicyForNode(node);
InertiaCalculator calculator(policy, mesh, &mesh_inertia_);
const auto [volume, p_GoGcm_G, G_GGo_G] = calculator.Calc(*geom.shape);
if (calculator.used_convex_hull_fallback()) {
// When the Mujoco parser falls back to using a convex hull, it prints
Expand All @@ -904,7 +914,7 @@ class MujocoParser {
ParseScalarAttribute(node, "density", &density);
mass = volume * density;
}
SpatialInertia<double> M_GGo_G(mass, p_GoGcm_G, G_GGo_G);
SpatialInertia<double> M_GGo_G(mass, p_GoGcm_G, G_GGo_G); // XXX throw

// Shift spatial inertia from Go to Bo and express it in the B frame.
const math::RotationMatrix<double>& R_BG = geom.X_BG.rotation();
Expand Down
9 changes: 9 additions & 0 deletions multibody/parsing/test/detail_mesh_parser_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include <filesystem>
#include <optional>

#include <gmock/gmock.h>
#include <gtest/gtest.h>

#include "drake/common/find_resource.h"
Expand Down Expand Up @@ -254,6 +255,14 @@ TEST_F(MeshParserTest, CorrectMass) {
I_BBo_B_expected.CopyToFullMatrix6(), 1e-12));
}

TEST_F(MeshParserTest, ZeroVolume) {
// A 2x2x2 (meter) box centered on its canonical frame.
const std::string obj_path = FindResourceOrThrow(
"drake/geometry/test/bad_geometry_volume_zero.obj");
AddModelFromMeshFile(obj_path, "body");
EXPECT_THAT(TakeError(), ::testing::MatchesRegex(".*volume.*is 0.*"));
}

// When the plant has been registered as a SceneGraph geometry source, we should
// get illustration, perception, and proximity roles associated with the body.
TEST_F(MeshParserTest, RegisteredGeometry) {
Expand Down
9 changes: 3 additions & 6 deletions multibody/parsing/test/detail_mujoco_parser_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -789,8 +789,6 @@ TEST_F(BoxMeshTest, MeshFileScaleViaDefault) {
// CalcSpatialInertia() cannot necessarily compute a physical spatial inertia
// for meshes which don't adhere to its requirements. The parser detects this
// and provides a fallback so that it doesn't choke.
// Per #21666 the failure is reported by throwing, in the future it will be
// via some non-throwing protocol.
TEST_F(MujocoParserTest, BadMeshSpatialInertiaFallback) {
// This obj is known to produce a non-physical spatial inertia in
// CalcSpatialInertia().
Expand All @@ -799,10 +797,8 @@ TEST_F(MujocoParserTest, BadMeshSpatialInertiaFallback) {
ASSERT_EQ(rlocation.error, "");
const geometry::Mesh bad_mesh(rlocation.abspath, 1.0);

// For now, we know the spatial inertia is bad because it throws. When #21666
// is fixed, it will be some other mechanism. Evolve *this* test to match
// that API, but otherwise keep this confirmation that the mesh in question
// truly is "bad".
// We know the spatial inertia is bad because CalcSpatialInertia()
// throws. Keep this confirmation that the mesh in question truly is "bad".
DRAKE_EXPECT_THROWS_MESSAGE(CalcSpatialInertia(bad_mesh, 1.0),
".*IsPhysicallyValid[\\s\\S]*");

Expand All @@ -819,6 +815,7 @@ TEST_F(MujocoParserTest, BadMeshSpatialInertiaFallback) {
)""", rlocation.abspath);

EXPECT_NO_THROW(AddModelFromString(xml, "test"));
EXPECT_THAT(TakeWarning(), MatchesRegex(".*IsPhysicallyValid.*"));
EXPECT_THAT(TakeWarning(), MatchesRegex(".*fallback.*"));
// Note: This test doesn't cover the properties of the fallback; just the fact
// that we're using it (and not choking).
Expand Down
Loading