Skip to content

Commit

Permalink
MakeConvexHull now supports glTF files (RobotLocomotion#21131)
Browse files Browse the repository at this point in the history
We're using VTK to parse the glTF file. For VTK's parser to work, it needs
the OpenGl2 rendering artifacts initialized. This required moving VTK
module initialization out of `internal_render_engine_vtk.cc` and into its
own compilation unit to be shared.

It exercises the API in planar_scenegraph_visualizer.

While the API could probably be promoted to part of the stable API, that
decision is being deferred for now. It is bound as _MakeConvexHull.
  • Loading branch information
SeanCurtis-TRI authored Mar 13, 2024
1 parent 7eb1be6 commit 180150d
Show file tree
Hide file tree
Showing 13 changed files with 288 additions and 34 deletions.
8 changes: 8 additions & 0 deletions bindings/pydrake/geometry/geometry_py_hydro.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#include "drake/bindings/pydrake/common/type_safe_index_pybind.h"
#include "drake/bindings/pydrake/documentation_pybind.h"
#include "drake/geometry/geometry_roles.h"
#include "drake/geometry/proximity/make_convex_hull_mesh.h"
#include "drake/geometry/proximity/obj_to_surface_mesh.h"
#include "drake/geometry/proximity/polygon_surface_mesh.h"
#include "drake/geometry/proximity/polygon_surface_mesh_field.h"
Expand Down Expand Up @@ -267,6 +268,13 @@ void DoScalarIndependentDefinitions(py::module m) {
DefCopyAndDeepCopy(&cls);
}

// MakeConvexHull
{
constexpr char internal_doc[] = "(internal use only)";
m.def("_MakeConvexHull", &drake::geometry::internal::MakeConvexHull,
py::arg("shape"), internal_doc);
}

m.def(
"ReadObjToTriangleSurfaceMesh",
[](const std::string& filename, double scale) {
Expand Down
5 changes: 5 additions & 0 deletions bindings/pydrake/geometry/test/hydro_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -248,3 +248,8 @@ def test_read_obj_to_surface_mesh(self):
]
for i, expected in enumerate(expected_vertices):
self.assertListEqual(list(vertices[i]), expected)

def test_make_convex_hull(self):
mesh_path = FindResourceOrThrow("drake/geometry/test/quad_cube.obj")
hull = mut._MakeConvexHull(mut.Convex(mesh_path))
self.assertIsInstance(hull, mut.PolygonSurfaceMesh)
24 changes: 12 additions & 12 deletions bindings/pydrake/systems/planar_scenegraph_visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
from pydrake.common.deprecation import _warn_deprecated
from pydrake.common.value import Value
from pydrake.geometry import (
_MakeConvexHull,
Box,
Convex,
Cylinder,
Expand Down Expand Up @@ -244,9 +245,11 @@ def _build_body_patches(self, use_random_colors,
for pt in sample_pts])

elif isinstance(shape, (Mesh, Convex)):
# Legacy behavior for looking for a .obj when the extension
# is not recognized.
filename = shape.filename()
base, ext = os.path.splitext(filename)
if (ext.lower() != ".obj"
if (ext.lower() not in [".obj", ".vtk", ".gltf"]
and substitute_collocated_mesh_files):
# Check for a co-located .obj file (case insensitive).
for f in glob.glob(base + '.*'):
Expand All @@ -261,17 +264,14 @@ def _build_body_patches(self, use_random_colors,
if not os.path.exists(filename):
raise FileNotFoundError(errno.ENOENT, os.strerror(
errno.ENOENT), filename)
# Get mesh scaling.
scale = shape.scale()
mesh = ReadObjToTriangleSurfaceMesh(filename, scale)
patch_G = np.vstack(mesh.vertices())

# Only store the vertices of the (3D) convex hull of the
# mesh, as any interior vertices will still be interior
# vertices after projection, and will therefore be removed
# in _update_body_fill_verts().
vpoly = optimization.VPolytope(patch_G.T)
patch_G = vpoly.GetMinimalRepresentation().vertices()
temp_mesh = Mesh(filename, shape.scale())
# TODO(21125): When Convex shape *always* has a
# convex hull available, use it instead of recomputing it
# here.
convex_hull = _MakeConvexHull(temp_mesh)
patch_G = np.empty((3, convex_hull.num_vertices()))
for i in range(convex_hull.num_vertices()):
patch_G[:, i] = convex_hull.vertex(i)

elif isinstance(shape, HalfSpace):
# For a half space, we'll simply create a large box with
Expand Down
21 changes: 21 additions & 0 deletions geometry/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -679,6 +679,18 @@ drake_cc_library(
],
)

drake_cc_library(
name = "vtk_opengl_init",
srcs = ["vtk_opengl_init.cc"],
internal = True,
visibility = ["//geometry:__subpackages__"],
deps = [
"@vtk_internal//:vtkCommonCore",
"@vtk_internal//:vtkRenderingOpenGL2",
],
alwayslink = True,
)

drake_cc_googletest(
name = "meshcat_visualizer_test",
data = [
Expand All @@ -699,6 +711,15 @@ drake_cc_googletest(

# -----------------------------------------------------

filegroup(
name = "test_gltf_files",
testonly = 1,
srcs = [
"test/cube_with_hole.bin",
"test/cube_with_hole.gltf",
],
)

filegroup(
name = "test_obj_files",
testonly = 1,
Expand Down
7 changes: 7 additions & 0 deletions geometry/proximity/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -482,7 +482,12 @@ drake_cc_library(
"//common:essential",
"//common:find_resource",
"//geometry:read_obj",
"//geometry:vtk_opengl_init",
"//math:geometric_transform",
"@qhull_internal//:qhull",
"@vtk_internal//:vtkCommonCore",
"@vtk_internal//:vtkIOImport",
"@vtk_internal//:vtkRenderingCore",
],
)

Expand Down Expand Up @@ -1237,6 +1242,7 @@ drake_cc_googletest(
drake_cc_googletest(
name = "make_convex_hull_mesh_test",
data = [
"//geometry:test_gltf_files",
"//geometry:test_obj_files",
"//geometry:test_vtk_files",
"//geometry/render:test_models",
Expand All @@ -1246,6 +1252,7 @@ drake_cc_googletest(
"//common:find_resource",
"//common:temp_directory",
"//common/test_utilities:expect_throws_message",
"@nlohmann_internal//:nlohmann",
],
)

Expand Down
83 changes: 71 additions & 12 deletions geometry/proximity/make_convex_hull_mesh.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,16 @@
#include <utility>
#include <vector>

// To ease build system upkeep, we annotate VTK includes with their deps.
#include <fmt/format.h>
#include <libqhullcpp/Qhull.h>
#include <libqhullcpp/QhullFacet.h>
#include <libqhullcpp/QhullVertexSet.h>
#include <vtkGLTFImporter.h> // vtkIOImport
#include <vtkMapper.h> // vtkCommonCore
#include <vtkMatrix4x4.h> // vtkCommonMath
#include <vtkPolyData.h> // vtkCommonDataModel
#include <vtkRenderer.h> // vtkRenderingCore

#include "drake/common/find_resource.h"
#include "drake/common/fmt_eigen.h"
Expand All @@ -18,13 +24,17 @@
#include "drake/geometry/proximity/volume_mesh.h"
#include "drake/geometry/proximity/vtk_to_volume_mesh.h"
#include "drake/geometry/read_obj.h"
#include "drake/math/rigid_transform.h"
#include "drake/math/rotation_matrix.h"

namespace drake {
namespace geometry {
namespace internal {
namespace {

using Eigen::Vector3d;
using math::RigidTransformd;
using math::RotationMatrixd;

/* Used for ordering polygon vertices according to their angular distance from
a reference direction. See OrderPolyVertices(). */
Expand Down Expand Up @@ -100,8 +110,8 @@ struct VertexCloud {
Vector3d interior_point;
};

/* Simply reads the vertices from an OBJ or VTK file referred to by either a
Mesh or Convex shape. Supports getting the vertices for MakeConvexHull.
/* Simply reads the vertices from an OBJ, VTK or glTF file referred to by either
a Mesh or Convex shape. Supports getting the vertices for MakeConvexHull.
When calling reify, the user data should be an instance of VertexCloud. The
reifier will write the results into that instance. */
Expand Down Expand Up @@ -129,17 +139,20 @@ class VertexReader final : public ShapeReifier {
ReadObjVertices(filename, scale, &cloud.vertices);
} else if (extension == ".vtk") {
ReadVtkVertices(filename, scale, &cloud.vertices);
} else if (extension == ".gltf") {
ReadGltfVertices(filename, scale, &cloud.vertices);
} else {
throw std::runtime_error(fmt::format(
"MakeConvexHull only applies to obj and vtk meshes; given file: {}.",
"MakeConvexHull only applies to obj, vtk, and gltf meshes; "
"given file: {}.",
filename));
}

if (cloud.vertices.size() < 3) {
throw std::runtime_error(
fmt::format("MakeConvexHull() cannot be used on a mesh with fewer "
"than three vertices; found {} vertices in file: {}.",
cloud.vertices.size(), filename));
throw std::runtime_error(fmt::format(
"MakeConvexHull() cannot be used on a mesh with fewer than three "
"vertices; found {} vertices in file: {}.",
cloud.vertices.size(), filename));
}

/* Characterizes planarity. */
Expand Down Expand Up @@ -180,6 +193,51 @@ class VertexReader final : public ShapeReifier {
*vertices = volume_mesh.vertices();
}

// Multiplies the position vector p_AQ by the transform T_BA, returning p_BQ.
Vector3d VtkMultiply(vtkMatrix4x4* T_BA, const Vector3d& p_AQ) {
double p_in[] = {p_AQ.x(), p_AQ.y(), p_AQ.z(), 1};
double p_out[4];
T_BA->MultiplyPoint(p_in, p_out);
return Vector3d(p_out);
}

void ReadGltfVertices(std::string_view filename, double scale,
std::vector<Vector3d>* vertices) {
vtkNew<vtkGLTFImporter> importer;
importer->SetFileName(filename.data());
importer->Update();

auto* renderer = importer->GetRenderer();
DRAKE_DEMAND(renderer != nullptr);

if (renderer->VisibleActorCount() == 0) {
throw std::runtime_error(fmt::format(
"MakeConvexHull() found no vertices in the file '{}'.", filename));
}

// The relative transform from the file's frame F to the geometry's frame G.
// (rotation from y-up to z-up). The scale is handled separately.
const RigidTransformd X_GF(RotationMatrixd::MakeXRotation(M_PI / 2));

auto* actors = renderer->GetActors();
actors->InitTraversal();
while (vtkActor* actor = actors->GetNextActor()) {
// 1. Extract PolyData from actor.
auto* poly_data =
dynamic_cast<vtkPolyData*>(actor->GetMapper()->GetInput());
DRAKE_DEMAND(poly_data != nullptr);
// 2. For each vertex, transform it to the file frame (based on the
// actor's user transform), and then into the geometry frame using the
// scale and rotation.
vtkMatrix4x4* T_FA = actor->GetUserMatrix();
for (vtkIdType vi = 0; vi < poly_data->GetNumberOfPoints(); ++vi) {
const Vector3d p_AV(poly_data->GetPoint(vi));
const Vector3d p_FV = VtkMultiply(T_FA, p_AV);
vertices->emplace_back((X_GF * p_FV) * scale);
}
}
}

/* Given a set of vertices, attempts to find a plane that reliably spans
three vertices. The normal is defined as n = a x b / |a x b| where
a = v[j] - v[0] and
Expand All @@ -205,7 +263,8 @@ class VertexReader final : public ShapeReifier {
if (v == ssize(vertices)) {
throw std::runtime_error(
fmt::format("MakeConvexHull failed because all vertices in the mesh "
"were within a sphere with radius 1e-12 for file: {}.",
"were within a "
"sphere with radius 1e-12 for file: {}.",
filename));
}
a.normalize();
Expand All @@ -221,10 +280,10 @@ class VertexReader final : public ShapeReifier {
}

if (v == ssize(vertices)) {
throw std::runtime_error(
fmt::format("MakeConvexHull failed because all vertices in the mesh "
"appear to be co-linear for file: {}.",
filename));
throw std::runtime_error(fmt::format(
"MakeConvexHull failed because all vertices in the mesh appear to be "
"co-linear for file: {}.",
filename));
}
return n_candidate.normalized();
}
Expand Down
2 changes: 1 addition & 1 deletion geometry/proximity/make_convex_hull_mesh.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ namespace internal {
@param shape The shape to bound.
@throws if `shape` is not an instance of Mesh or Convex.
@throws if `shape` references anything but an .obj or .vtk volume mesh.
@throws if `shape` references anything but an .obj, .vtk volume mesh, or .gltf.
@throws if the referenced mesh data is degenerate (insufficient number of
vertices, co-linear or coincident vertices, etc.) All of the
vertices lying on a plane is *not* degenerate.
Expand Down
Loading

0 comments on commit 180150d

Please sign in to comment.