Skip to content

Commit

Permalink
[geometry] Allow some sub-optimal uses for vtk volume mesh files (Rob…
Browse files Browse the repository at this point in the history
…otLocomotion#20278)

Accept vtk volume mesh files in some cases where only the surface mesh
or its convex hull might actually be used. This is intended to ease
step-wise refinement of models to optimize them for use with
hydroelastic contact.

Also, make some improvements to error messages in a few places.
  • Loading branch information
rpoyner-tri authored Oct 16, 2023
1 parent 9540a5b commit e8e8a32
Show file tree
Hide file tree
Showing 11 changed files with 385 additions and 82 deletions.
1 change: 1 addition & 0 deletions geometry/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -653,6 +653,7 @@ filegroup(
testonly = 1,
srcs = [
"test/cube_as_6_squares.vtk",
"test/extruded_u_volume_mesh.vtk",
"test/non_convex_mesh.vtk",
"test/one_negative_tetrahedron.vtk",
"test/one_tetrahedron.vtk",
Expand Down
14 changes: 13 additions & 1 deletion geometry/geometry_file_formats_doxygen.h
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,19 @@ namespace geometry {
Depending on the application (hydroelastics or deformable bodies), not every
tetrahedralization is created equal. There are best practices for each domain
which must be followed to get best results. More details on these best
practices are coming.
practices are coming.
In addition to specifying the tetrahedral mesh for deformable or compliant
hydroelastic geometries, the .vtk file can be used more generally:
- When specified as Convex without hydroelastic properties, it produces the
same representation for point contact as if you'd provided an .obj of
just the surface polygons.
- When specified as Mesh without hydroelastic properties, it is treated as
a non-convex surface mesh; its convex hull is used for point contact.
N.B. The .vtk file must still define a tetrahedral mesh and *not* a surface
mesh.
@section geometry_materials Drake materials and the specification heuristic
Expand Down
34 changes: 25 additions & 9 deletions geometry/proximity/hydroelastic_internal.cc
Original file line number Diff line number Diff line change
Expand Up @@ -272,16 +272,24 @@ std::optional<RigidGeometry> MakeRigidRepresentation(

std::optional<RigidGeometry> MakeRigidRepresentation(
const Convex& convex_spec, const ProximityProperties&) {
if (convex_spec.extension() != ".obj") {
throw std::runtime_error(fmt::format(
"hydroelastic::MakeRigidRepresentation(): for rigid hydroelastic "
"Convex shapes can only use .obj files; given: {}",
convex_spec.filename()));
}
// Convex does not use any properties.
auto mesh =
make_unique<TriangleSurfaceMesh<double>>(ReadObjToTriangleSurfaceMesh(
convex_spec.filename(), convex_spec.scale()));
std::unique_ptr<TriangleSurfaceMesh<double>> mesh;

const std::string extension = convex_spec.extension();
if (extension == ".obj") {
mesh =
make_unique<TriangleSurfaceMesh<double>>(ReadObjToTriangleSurfaceMesh(
convex_spec.filename(), convex_spec.scale()));
} else if (extension == ".vtk") {
mesh = make_unique<TriangleSurfaceMesh<double>>(
ConvertVolumeToSurfaceMesh(MakeVolumeMeshFromVtk<double>(convex_spec)));
} else {
throw(std::runtime_error(
fmt::format("hydroelastic::MakeRigidRepresentation(): for rigid "
"hydroelastic Convex "
"shapes can only use .obj or .vtk files; given: {}",
convex_spec.filename())));
}

return RigidGeometry(RigidMesh(std::move(mesh)));
}
Expand Down Expand Up @@ -395,6 +403,14 @@ std::optional<SoftGeometry> MakeSoftRepresentation(
const Convex& convex_spec, const ProximityProperties& props) {
PositiveDouble validator("Convex", "soft");

const std::string extension = convex_spec.extension();
if (extension != ".obj") {
throw(std::runtime_error(
fmt::format("hydroelastic::MakeSoftRepresentation(): for compliant "
"hydroelastic Convex "
"shapes can only use .obj files; given: {}",
convex_spec.filename())));
}
auto mesh = make_unique<VolumeMesh<double>>(
MakeConvexVolumeMesh<double>(convex_spec));

Expand Down
14 changes: 7 additions & 7 deletions geometry/proximity/make_mesh_from_vtk.cc
Original file line number Diff line number Diff line change
Expand Up @@ -13,20 +13,20 @@ namespace geometry {
namespace internal {

template <typename T>
VolumeMesh<T> MakeVolumeMeshFromVtk(const Mesh& mesh_spec) {
const std::string& vtk_file_name = mesh_spec.filename();
VolumeMesh<double> read_mesh =
ReadVtkToVolumeMesh(vtk_file_name, mesh_spec.scale());
VolumeMesh<T> MakeVolumeMeshFromVtk(const std::filesystem::path& filename,
double scale) {
VolumeMesh<double> read_mesh = ReadVtkToVolumeMesh(filename, scale);

for (int e = 0; e < read_mesh.num_elements(); ++e) {
if (read_mesh.CalcTetrahedronVolume(e) <= 0.) {
throw std::runtime_error(fmt::format(
"MakeVolumeMeshFromVtk: "
"MakeVolumeMeshFromVtk('{}', {}): "
"The {}-th tetrahedron (index start at 0) with "
"vertices {}, {}, {}, {} has non-positive volume, "
"so you might want to switch two consecutive vertices.",
e, read_mesh.element(e).vertex(0), read_mesh.element(e).vertex(1),
read_mesh.element(e).vertex(2), read_mesh.element(e).vertex(3)));
filename.string(), scale, e, read_mesh.element(e).vertex(0),
read_mesh.element(e).vertex(1), read_mesh.element(e).vertex(2),
read_mesh.element(e).vertex(3)));
}
}

Expand Down
17 changes: 15 additions & 2 deletions geometry/proximity/make_mesh_from_vtk.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,8 @@
#pragma once

#include <filesystem>
#include <string>

#include "drake/geometry/proximity/volume_mesh.h"
#include "drake/geometry/shape_specification.h"

Expand All @@ -10,7 +13,8 @@ namespace internal {
/* Creates a VolumeMesh of a possibly non-convex object from a VTK file
containing its tetrahedral mesh. It complements MakeConvexVolumeMesh().
@param[in] mesh The mesh specification containing VTK file name.
@param[in] filename VTK file name.
@param[in] scale scale parameter.
@retval volume_mesh
@tparam_nonsymbolic_scalar
Expand All @@ -22,7 +26,16 @@ namespace internal {
instead of a tetrahedral mesh.
*/
template <typename T>
VolumeMesh<T> MakeVolumeMeshFromVtk(const Mesh& mesh);
VolumeMesh<T> MakeVolumeMeshFromVtk(const std::filesystem::path& filename,
double scale);

/* Overload the 2-argument MakeVolumeMeshFromVtk() to take filename and scale
from either Mesh or Convex shape specifications.
*/
template <typename T, typename Shape>
VolumeMesh<T> MakeVolumeMeshFromVtk(const Shape& shape) {
return MakeVolumeMeshFromVtk<T>(shape.filename(), shape.scale());
}

} // namespace internal
} // namespace geometry
Expand Down
16 changes: 15 additions & 1 deletion geometry/proximity/test/hydroelastic_internal_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -661,11 +661,25 @@ TEST_F(HydroelasticRigidGeometryTest, Mesh) {
// is made.
TEST_F(HydroelasticRigidGeometryTest, Convex) {
{
SCOPED_TRACE("Rigid Convex");
SCOPED_TRACE("Rigid Convex from Obj file");
std::string file = FindResourceOrThrow("drake/geometry/test/quad_cube.obj");
TestRigidMeshTypeFromObj<Convex>(file);
}

{
SCOPED_TRACE("Rigid Convex from VTK file");
std::string file =
FindResourceOrThrow("drake/geometry/test/one_tetrahedron.vtk");
// Empty props since its contents do not matter.
const ProximityProperties props;
std::optional<RigidGeometry> geometry =
MakeRigidRepresentation(Convex(file), props);
ASSERT_NE(geometry, std::nullopt);
const TriangleSurfaceMesh<double>& surface_mesh = geometry->mesh();
EXPECT_EQ(surface_mesh.num_vertices(), 4);
EXPECT_EQ(surface_mesh.num_triangles(), 4);
}

{
SCOPED_TRACE("Rigid Convex, unsupported extension");
DRAKE_EXPECT_THROWS_MESSAGE(TestRigidMeshTypeFromObj<Convex>("invalid.stl"),
Expand Down
2 changes: 1 addition & 1 deletion geometry/proximity/test/make_mesh_from_vtk_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ GTEST_TEST(MakeVolumeMeshFromVtkTest, NegativeVolumeThrow) {

DRAKE_EXPECT_THROWS_MESSAGE(
MakeVolumeMeshFromVtk<double>(negative_mesh_specification),
"MakeVolumeMeshFromVtk: .* tetrahedron.*"
"MakeVolumeMeshFromVtk.* tetrahedron.*"
"with vertices .* has non-positive volume, "
"so you might want to switch two consecutive vertices.");
}
Expand Down
65 changes: 41 additions & 24 deletions geometry/proximity_engine.cc
Original file line number Diff line number Diff line change
Expand Up @@ -463,22 +463,33 @@ class ProximityEngine<T>::Impl : public ShapeReifier {
ProcessGeometriesForDeformableContact(capsule, user_data);
}

// For proximity role, a Convex surface mesh can come from a surface mesh in
// obj file or a tetrahedral mesh in vtk file, from which we extract its
// surface.
void ImplementGeometry(const Convex& convex, void* user_data) override {
const ReifyData& data = *static_cast<ReifyData*>(user_data);
const HydroelasticType type = data.properties.GetPropertyOrDefault(
kHydroGroup, kComplianceType, HydroelasticType::kUndefined);
if (type == HydroelasticType::kUndefined && convex.extension() != ".obj") {
throw std::runtime_error(
fmt::format("ProximityEngine: Convex shapes for non-hydroelastic "
"contact only support .obj files; got ({}) instead.",
convex.filename()));
shared_ptr<const std::vector<Vector3d>> shared_verts;
shared_ptr<std::vector<int>> shared_faces;
int num_faces{0};
if (convex.extension() == ".obj") {
// Don't bother triangulating; Convex supports polygons.
std::tie(shared_verts, shared_faces, num_faces) =
ReadObjFile(convex.filename(), convex.scale(),
false /* triangulate */);
} else if (convex.extension() == ".vtk") {
auto surface_mesh = ConvertVolumeToSurfaceMesh(
ReadVtkToVolumeMesh(convex.filename()));
shared_verts = make_shared<const std::vector<Vector3d>>(
surface_mesh.vertices());
shared_faces = make_shared<std::vector<int>>();
} else {
throw std::runtime_error(fmt::format(
"ProximityEngine: Convex shapes only support .obj or .vtk files;"
" got ({}) instead.",
convex.filename()));
}
// Don't bother triangulating; Convex supports polygons.
const auto [vertices, faces, num_faces] =
ReadObjFile(convex.filename(), convex.scale(), false /* triangulate */);

// Create fcl::Convex.
auto fcl_convex = make_shared<fcl::Convexd>(vertices, num_faces, faces);
auto fcl_convex =
make_shared<fcl::Convexd>(shared_verts, num_faces, shared_faces);

TakeShapeOwnership(fcl_convex, user_data);
ProcessHydroelastic(convex, user_data);
Expand Down Expand Up @@ -536,18 +547,24 @@ class ProximityEngine<T>::Impl : public ShapeReifier {
shared_verts = make_shared<const std::vector<Vector3d>>(
hydroelastic_geometries_.rigid_geometry(data.id).mesh().vertices());
} else {
if (mesh.extension() != ".obj") {
throw std::runtime_error(
fmt::format("ProximityEngine: Mesh shapes for non-hydroelastic "
"contact only support .obj files; got ({}) instead.",
mesh.filename()));
if (mesh.extension() == ".vtk") {
// TODO(rpoyner-tri): could take convex hull here.
shared_verts = make_shared<const std::vector<Vector3d>>(
ConvertVolumeToSurfaceMesh(
ReadVtkToVolumeMesh(mesh.filename()))
.vertices());
} else if (mesh.extension() == ".obj") {
// Don't bother triangulating; we're ignoring the faces.
std::tie(shared_verts, std::ignore, std::ignore) =
ReadObjFile(mesh.filename(), mesh.scale(), false /* triangulate */);
} else {
// TODO(SeanCurtis-TRI) Add a troubleshooting entry to give more
// helpful advice.
throw std::runtime_error(fmt::format(
"ProximityEngine: Mesh shapes for non-hydroelastic "
"contact only support .obj or .vtk files; got ({}) instead.",
mesh.filename()));
}
// TODO(SeanCurtis-TRI) Add a troubleshooting entry to give more helpful
// advice.

// Don't bother triangulating; we're ignoring the faces.
std::tie(shared_verts, std::ignore, std::ignore) =
ReadObjFile(mesh.filename(), mesh.scale(), false /* triangulate */);
}

// Note: the strategy here is to use an *invalid* fcl::Convex shape for the
Expand Down
5 changes: 3 additions & 2 deletions geometry/query_object.h
Original file line number Diff line number Diff line change
Expand Up @@ -328,8 +328,9 @@ class QueryObject {
<a href="https://docs.google.com/document/d/1VZtVsxIjOLKvgQ8SNSrF6PtWuPW5z9PP7-dQuxfmqpc/edit?usp=sharing">
document</a> provides guidance how to generate a tetrahedral mesh
in a VTK file from a surface mesh in an OBJ file.
- ᵇ For rigid Mesh, please specify a surface mesh
in an OBJ file in Mesh(filename).
- ᵇ For rigid Mesh, please specify a surface mesh in an OBJ file in
Mesh(filename). A tetrahedral mesh in a VTK file can also be
specified.
- ᶜ For both compliant Convex and rigid Convex, please specify a surface
mesh in an OBJ file in Convex(filename).
Expand Down
Loading

0 comments on commit e8e8a32

Please sign in to comment.