Skip to content

Commit

Permalink
[geometry] Remove the non-BVH interface for rigid-soft mesh intersect…
Browse files Browse the repository at this point in the history
…ion (RobotLocomotion#14110)

For historical reasons, computing intersection between a soft volume mesh
and a rigid surface mesh had two separate APIs. One used broadphase
acceleration with a bounding volume hierarchy (BVH) one did not. Both
APIs were propagated as a basis for measuring improvement. The need for
both APIs is long gone. So, we'll simplify the API and eliminate the slow
version. Going forward, improvements should be against strictly the best
possible results. This change had several implications:

 - mesh_intersection_benchmark now only considers one case -- it reports
   the performance of queries with the *current* BVH implementation.
 - Unit tests in mesh_intersection_test would exploit the BVH-free API to
   shorten the tests. They needed to be expanded to use the BVH API.
   - One test in particular would produce a smoke test confirming that the
     test could be used with AutoDiffXd-valued meshes. That used the old
     BVH-free API. In removing that API, we need to be able to build a
     BVH for an AutoDiffXd-valued mesh.
 - Bvh and obb (and tests) have been updated to allow constructing a BVH
   for an AutoDiffXd-valued mesh.
 - Incidentally, cleaned up names of meshes to match the quantity_F
   notation.
  • Loading branch information
SeanCurtis-TRI authored Sep 28, 2020
1 parent e7112e6 commit aef3590
Show file tree
Hide file tree
Showing 11 changed files with 174 additions and 494 deletions.
8 changes: 4 additions & 4 deletions geometry/benchmarking/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ designed so users can assess the relative cost of the renderers on their own
hardware configuration, aiding in design decisions for understanding the cost of
renderer choice.
* [mesh_intersection_benchmark.cc](./mesh_intersection_benchmark.cc):
Benchmark program to compare different mesh intersection optimizations with
varying mesh attributes and overlaps. It is targeted toward developers during
the process of optimizing the performance of hydroelastic contact and may be
removed once sufficient work has been done in that effort.
Benchmark program to evaluate bounding volume hierarchy impact on mesh-mesh
intersections across varying mesh attributes and overlaps. It is targeted toward
developers during the process of optimizing the performance of hydroelastic
contact and may be removed once sufficient work has been done in that effort.
144 changes: 33 additions & 111 deletions geometry/benchmarking/mesh_intersection_benchmark.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,12 +14,11 @@ namespace internal {
/* @defgroup mesh_intersection_benchmarks Mesh Intersection Benchmarks
@ingroup proximity_queries
The benchmark compares mesh intersection techniques between soft and rigid
meshes.
The benchmark evaluates mesh intersection between soft and rigid meshes.
It computes the contact surface formed from the intersection of an ellipsoid
and a sphere both using and not using broad-phase culling (via a bounding
volume hierarchy). Arguments include:
and a sphere using broad-phase culling (via a bounding volume hierarchy).
Arguments include:
- __resolution__: An enumeration in the integer range from 0 to 3 that guides
the level of mesh refinement, where 0 produces the coarsest meshes and 3
produces the finest meshes.
Expand Down Expand Up @@ -64,59 +63,33 @@ Load Average: 21.52, 41.04, 26.99
---------------------------------------------------------------------------------------------------- // NOLINT(*)
Benchmark Time CPU Iterations Line Number // NOLINT(*)
---------------------------------------------------------------------------------------------------- // NOLINT(*)
MeshIntersectionBenchmark/WithoutBVH/0/4/0/min_time:2.000 0.903 ms 0.903 ms 3297 [1] // NOLINT(*)
MeshIntersectionBenchmark/WithoutBVH/1/4/0/min_time:2.000 5.74 ms 5.74 ms 456 [2] // NOLINT(*)
MeshIntersectionBenchmark/WithoutBVH/2/4/0/min_time:2.000 19.1 ms 19.1 ms 129 [3] // NOLINT(*)
MeshIntersectionBenchmark/WithoutBVH/3/4/0/min_time:2.000 530 ms 530 ms 5 [4] // NOLINT(*)
MeshIntersectionBenchmark/WithoutBVH/2/0/0/min_time:2.000 15.1 ms 15.1 ms 189 [5] // NOLINT(*)
MeshIntersectionBenchmark/WithoutBVH/2/1/0/min_time:2.000 15.4 ms 15.4 ms 178 [6] // NOLINT(*)
MeshIntersectionBenchmark/WithoutBVH/2/2/0/min_time:2.000 15.9 ms 15.9 ms 176 [7] // NOLINT(*)
MeshIntersectionBenchmark/WithoutBVH/2/3/0/min_time:2.000 18.3 ms 18.3 ms 150 [8] // NOLINT(*)
MeshIntersectionBenchmark/WithoutBVH/2/4/1/min_time:2.000 19.1 ms 19.1 ms 147 [9] // NOLINT(*)
MeshIntersectionBenchmark/WithoutBVH/2/4/2/min_time:2.000 19.0 ms 19.0 ms 147 [10] // NOLINT(*)
MeshIntersectionBenchmark/WithoutBVH/2/4/3/min_time:2.000 19.2 ms 19.2 ms 145 [11] // NOLINT(*)
MeshIntersectionBenchmark/WithoutBVH/2/3/1/min_time:2.000 17.9 ms 17.9 ms 156 [12] // NOLINT(*)
MeshIntersectionBenchmark/WithoutBVH/2/2/2/min_time:2.000 15.6 ms 15.6 ms 180 [13] // NOLINT(*)
MeshIntersectionBenchmark/___WithBVH/0/4/0/min_time:2.000 0.629 ms 0.629 ms 4408 [14] // NOLINT(*)
MeshIntersectionBenchmark/___WithBVH/1/4/0/min_time:2.000 2.15 ms 2.15 ms 1328 [15] // NOLINT(*)
MeshIntersectionBenchmark/___WithBVH/2/4/0/min_time:2.000 3.14 ms 3.14 ms 893 [16] // NOLINT(*)
MeshIntersectionBenchmark/___WithBVH/3/4/0/min_time:2.000 14.3 ms 14.3 ms 192 [17] // NOLINT(*)
MeshIntersectionBenchmark/___WithBVH/2/0/0/min_time:2.000 0.000 ms 0.000 ms 54932081 [18] // NOLINT(*)
MeshIntersectionBenchmark/___WithBVH/2/1/0/min_time:2.000 0.023 ms 0.023 ms 119450 [19] // NOLINT(*)
MeshIntersectionBenchmark/___WithBVH/2/2/0/min_time:2.000 0.119 ms 0.119 ms 23142 [20] // NOLINT(*)
MeshIntersectionBenchmark/___WithBVH/2/3/0/min_time:2.000 1.87 ms 1.87 ms 1486 [21] // NOLINT(*)
MeshIntersectionBenchmark/___WithBVH/2/4/1/min_time:2.000 2.95 ms 2.95 ms 944 [22] // NOLINT(*)
MeshIntersectionBenchmark/___WithBVH/2/4/2/min_time:2.000 3.15 ms 3.15 ms 894 [23] // NOLINT(*)
MeshIntersectionBenchmark/___WithBVH/2/4/3/min_time:2.000 3.21 ms 3.21 ms 871 [24] // NOLINT(*)
MeshIntersectionBenchmark/___WithBVH/2/3/1/min_time:2.000 1.94 ms 1.94 ms 1448 [25] // NOLINT(*)
MeshIntersectionBenchmark/___WithBVH/2/2/2/min_time:2.000 0.127 ms 0.127 ms 22007 [26] // NOLINT(*)
MeshIntersectionBenchmark/RigidSoftMesh/0/4/0/min_time:2.000 0.629 ms 0.629 ms 4408 [14] // NOLINT(*)
MeshIntersectionBenchmark/RigidSoftMesh/1/4/0/min_time:2.000 2.15 ms 2.15 ms 1328 [15] // NOLINT(*)
MeshIntersectionBenchmark/RigidSoftMesh/2/4/0/min_time:2.000 3.14 ms 3.14 ms 893 [16] // NOLINT(*)
MeshIntersectionBenchmark/RigidSoftMesh/3/4/0/min_time:2.000 14.3 ms 14.3 ms 192 [17] // NOLINT(*)
MeshIntersectionBenchmark/RigidSoftMesh/2/0/0/min_time:2.000 0.000 ms 0.000 ms 54932081 [18] // NOLINT(*)
MeshIntersectionBenchmark/RigidSoftMesh/2/1/0/min_time:2.000 0.023 ms 0.023 ms 119450 [19] // NOLINT(*)
MeshIntersectionBenchmark/RigidSoftMesh/2/2/0/min_time:2.000 0.119 ms 0.119 ms 23142 [20] // NOLINT(*)
MeshIntersectionBenchmark/RigidSoftMesh/2/3/0/min_time:2.000 1.87 ms 1.87 ms 1486 [21] // NOLINT(*)
MeshIntersectionBenchmark/RigidSoftMesh/2/4/1/min_time:2.000 2.95 ms 2.95 ms 944 [22] // NOLINT(*)
MeshIntersectionBenchmark/RigidSoftMesh/2/4/2/min_time:2.000 3.15 ms 3.15 ms 894 [23] // NOLINT(*)
MeshIntersectionBenchmark/RigidSoftMesh/2/4/3/min_time:2.000 3.21 ms 3.21 ms 871 [24] // NOLINT(*)
MeshIntersectionBenchmark/RigidSoftMesh/2/3/1/min_time:2.000 1.94 ms 1.94 ms 1448 [25] // NOLINT(*)
MeshIntersectionBenchmark/RigidSoftMesh/2/2/2/min_time:2.000 0.127 ms 0.127 ms 22007 [26] // NOLINT(*)
Resulting contact surface sizes:
- WithoutBVH/0/4/0: 93.76 m^2, 448 triangles
- WithoutBVH/1/4/0: 93.76 m^2, 1592 triangles
- WithoutBVH/2/4/0: 107.59 m^2, 2848 triangles
- WithoutBVH/3/4/0: 111.67 m^2, 14336 triangles
- WithoutBVH/2/0/0: 0.00 m^2, 0 triangles
- WithoutBVH/2/1/0: 0.00 m^2, 0 triangles
- WithoutBVH/2/2/0: 1.50 m^2, 58 triangles
- WithoutBVH/2/3/0: 48.21 m^2, 2226 triangles
- WithoutBVH/2/4/1: 106.41 m^2, 3804 triangles
- WithoutBVH/2/4/2: 106.89 m^2, 3848 triangles
- WithoutBVH/2/4/3: 107.44 m^2, 3808 triangles
- WithoutBVH/2/3/1: 48.26 m^2, 2190 triangles
- WithoutBVH/2/2/2: 1.52 m^2, 62 triangles
- ___WithBVH/0/4/0: 93.76 m^2, 448 triangles
- ___WithBVH/1/4/0: 93.76 m^2, 1592 triangles
- ___WithBVH/2/4/0: 107.59 m^2, 2848 triangles
- ___WithBVH/3/4/0: 111.67 m^2, 14336 triangles
- ___WithBVH/2/0/0: 0.00 m^2, 0 triangles
- ___WithBVH/2/1/0: 0.00 m^2, 0 triangles
- ___WithBVH/2/2/0: 1.50 m^2, 58 triangles
- ___WithBVH/2/3/0: 48.21 m^2, 2226 triangles
- ___WithBVH/2/4/1: 106.41 m^2, 3804 triangles
- ___WithBVH/2/4/2: 106.89 m^2, 3848 triangles
- ___WithBVH/2/4/3: 107.44 m^2, 3808 triangles
- ___WithBVH/2/3/1: 48.26 m^2, 2190 triangles
- ___WithBVH/2/2/2: 1.52 m^2, 62 triangles
- RigidSoftMesh/0/4/0: 93.76 m^2, 448 triangles
- RigidSoftMesh/1/4/0: 93.76 m^2, 1592 triangles
- RigidSoftMesh/2/4/0: 107.59 m^2, 2848 triangles
- RigidSoftMesh/3/4/0: 111.67 m^2, 14336 triangles
- RigidSoftMesh/2/0/0: 0.00 m^2, 0 triangles
- RigidSoftMesh/2/1/0: 0.00 m^2, 0 triangles
- RigidSoftMesh/2/2/0: 1.50 m^2, 58 triangles
- RigidSoftMesh/2/3/0: 48.21 m^2, 2226 triangles
- RigidSoftMesh/2/4/1: 106.41 m^2, 3804 triangles
- RigidSoftMesh/2/4/2: 106.89 m^2, 3848 triangles
- RigidSoftMesh/2/4/3: 107.44 m^2, 3808 triangles
- RigidSoftMesh/2/3/1: 48.26 m^2, 2190 triangles
- RigidSoftMesh/2/2/2: 1.52 m^2, 62 triangles
```
Expand All @@ -129,9 +102,7 @@ Resulting contact surface sizes:
MeshIntersectionBenchmark/TestName/resolution/contact_overlap/rotation_factor/min_time
```
- __TestName__: One of
- __WithoutBVH__: Computes the intersection without broad-phase culling.
- __WithBVH__: Computes the intersection with broad-phase culling.
- __TestName__: RigidSoftMesh
- __resolution__: Affects the resolution of the ellipsoid and sphere
meshes. Valid values must be one of [0, 1, 2, 3], where 0 produces the
coarsest meshes and 3 produces the finest meshes. This is converted behind
Expand Down Expand Up @@ -163,22 +134,6 @@ Resulting contact surface sizes:
compute the intersection. The `Iterations` indicates how often the action was
performed to compute the average value. For more information see the [google
benchmark documentation](https://github.com/google/benchmark).
Now we can analyze the example output and draw some example inferences (not a
complete set of valid inferences):
- The BVH is increasingly effective as mesh resolution increases.
- For a resolution parameter of 2, broad-phase culling improves performance
by a factor of ~6X (see [3] vs [16]), while at a resolution parameter of
3 (a finer mesh), it improves by a factor of ~37X (see [4] vs [17]).
- As expected, the BVH is increasingly effective as contact overlap is
reduced.
- At a contact overlap parameter of 4, i.e. a maximal contact surface,
broad-phase culling improves performance by a factor of ~6X (see [3] vs
[16]), while at a contact overlap parameter of 2, i.e. a minimal contact
surface, it improves performance by a factor of ~133X (see [7] vs [20]).
- The offset in axis alignment has an apparently negligible impact on
performance.
*/

using Eigen::AngleAxis;
Expand Down Expand Up @@ -272,40 +227,7 @@ std::set<std::string> MeshIntersectionBenchmark::contact_surface_result_keys;
std::vector<std::string>
MeshIntersectionBenchmark::contact_surface_result_output;

BENCHMARK_DEFINE_F(MeshIntersectionBenchmark, WithoutBVH)
// NOLINTNEXTLINE(runtime/references)
(benchmark::State& state) {
SetupMeshes(state);
std::unique_ptr<SurfaceMesh<double>> surface_SR;
std::unique_ptr<SurfaceMeshFieldLinear<double, double>> e_SR;
std::vector<Vector3<double>> grad_eM_Ms;
for (auto _ : state) {
SurfaceVolumeIntersector<double>().SampleVolumeFieldOnSurface(
field_S_, mesh_R_, X_SR_, &surface_SR, &e_SR, &grad_eM_Ms);
}
RecordContactSurfaceResult(surface_SR.get(), "WithoutBVH", state);
}
BENCHMARK_REGISTER_F(MeshIntersectionBenchmark, WithoutBVH)
->Unit(benchmark::kMillisecond)
->MinTime(2)
->Args({0, 4, 0}) // 0 resolution, 4 contact overlap, 0 rotation factor.
->Args({1, 4, 0}) // 1 resolution, 4 contact overlap, 0 rotation factor.
->Args({2, 4, 0}) // 2 resolution, 4 contact overlap, 0 rotation factor.
->Args({3, 4, 0}) // 3 resolution, 4 contact overlap, 0 rotation factor.
->Args({2, 0, 0}) // 2 resolution, 0 contact overlap, 0 rotation factor.
->Args({2, 1, 0}) // 2 resolution, 1 contact overlap, 0 rotation factor.
->Args({2, 2, 0}) // 2 resolution, 2 contact overlap, 0 rotation factor.
->Args({2, 3, 0}) // 2 resolution, 3 contact overlap, 0 rotation factor.
->Args({2, 4, 1}) // 2 resolution, 4 contact overlap, 1 rotation factor.
->Args({2, 4, 2}) // 2 resolution, 4 contact overlap, 2 rotation factor.
->Args({2, 4, 3}) // 2 resolution, 4 contact overlap, 3 rotation factor.
->Args({2, 3, 1}) // 2 resolution, 3 contact overlap, 1 rotation factor.
->Args({2, 2, 2}); // 2 resolution, 2 contact overlap, 2 rotation factor.

// This test name is prefixed with underscores so that the total number of
// characters matches that of the first test, "WithoutBVH". This causes the
// final output to line up and makes it much easier to read.
BENCHMARK_DEFINE_F(MeshIntersectionBenchmark, ___WithBVH)
BENCHMARK_DEFINE_F(MeshIntersectionBenchmark, RigidSoftMesh)
// NOLINTNEXTLINE(runtime/references)
(benchmark::State& state) {
SetupMeshes(state);
Expand All @@ -319,9 +241,9 @@ BENCHMARK_DEFINE_F(MeshIntersectionBenchmark, ___WithBVH)
field_S_, bvh_S, mesh_R_, bvh_R, X_SR_, &surface_SR, &e_SR,
&grad_eM_Ms);
}
RecordContactSurfaceResult(surface_SR.get(), "___WithBVH", state);
RecordContactSurfaceResult(surface_SR.get(), "RigidSoftMesh", state);
}
BENCHMARK_REGISTER_F(MeshIntersectionBenchmark, ___WithBVH)
BENCHMARK_REGISTER_F(MeshIntersectionBenchmark, RigidSoftMesh)
->Unit(benchmark::kMillisecond)
->MinTime(2)
->Args({0, 4, 0}) // 0 resolution, 4 contact overlap, 0 rotation factor.
Expand Down
14 changes: 13 additions & 1 deletion geometry/proximity/bvh.cc
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@
#include <set>
#include <vector>

#include "drake/geometry/utilities.h"

namespace drake {
namespace geometry {
namespace internal {
Expand Down Expand Up @@ -114,7 +116,8 @@ Vector3d Bvh<MeshType>::ComputeCentroid(const MeshType& mesh,
const auto& element = mesh.element(i);
// Calculate average from all vertices.
for (int v = 0; v < kElementVertexCount; ++v) {
const auto& vertex = mesh.vertex(element.vertex(v)).r_MV();
const Vector3d& vertex =
convert_to_double(mesh.vertex(element.vertex(v)).r_MV());
centroid += vertex;
}
centroid /= kElementVertexCount;
Expand Down Expand Up @@ -149,3 +152,12 @@ template class drake::geometry::internal::Bvh<
drake::geometry::SurfaceMesh<double>>;
template class drake::geometry::internal::Bvh<
drake::geometry::VolumeMesh<double>>;

// TODO(SeanCurtis-tri) These are here to allow creating a BVH for an
// AutoDiffXd-valued mesh. Currently, the code doesn't strictly disallow this
// although projected uses are only double-valued. If we choose to definitively
// close the door on autodiff-valued meshes, we can remove these.
template class drake::geometry::internal::Bvh<
drake::geometry::SurfaceMesh<drake::AutoDiffXd>>;
template class drake::geometry::internal::Bvh<
drake::geometry::VolumeMesh<drake::AutoDiffXd>>;
18 changes: 14 additions & 4 deletions geometry/proximity/bvh.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,13 +23,13 @@ namespace internal {
template <class MeshType>
struct MeshTraits;

template <>
struct MeshTraits<SurfaceMesh<double>> {
template <typename T>
struct MeshTraits<SurfaceMesh<T>> {
static constexpr int kMaxElementPerBvhLeaf = 3;
};

template <>
struct MeshTraits<VolumeMesh<double>> {
template <typename T>
struct MeshTraits<VolumeMesh<T>> {
static constexpr int kMaxElementPerBvhLeaf = 1;
};

Expand Down Expand Up @@ -350,3 +350,13 @@ extern template class drake::geometry::internal::Bvh<
drake::geometry::SurfaceMesh<double>>;
extern template class drake::geometry::internal::Bvh<
drake::geometry::VolumeMesh<double>>;

// TODO(SeanCurtis-TRI): Remove support for building a Bvh on an AutoDiff-valued
// mesh after we've cleaned up the scalar types in hydroelastics. Specifically,
// this is here to support the unit tests in mesh_intersection_test.cc. Also
// the calls to convert_to_double should be removed.
// See issue #14136.
extern template class drake::geometry::internal::Bvh<
drake::geometry::SurfaceMesh<drake::AutoDiffXd>>;
extern template class drake::geometry::internal::Bvh<
drake::geometry::VolumeMesh<drake::AutoDiffXd>>;
Loading

0 comments on commit aef3590

Please sign in to comment.