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

[geometry] Accelerate initialization of compliant-hydroelastic nonconvex meshes #20798

Conversation

DamrongGuoy
Copy link
Contributor

@DamrongGuoy DamrongGuoy commented Jan 20, 2024

Speed up loading a tetrahedral-mesh VTK file. Improve pressure-field computation from O(mn) to O(n log n + m log n) using BVH, about 10X speed up in practice for moderate meshes.

Use BVH in CalcDistanceToSurfaceMesh.

Prequel of #20774.


This change is Reviewable

@DamrongGuoy DamrongGuoy force-pushed the draft_CalcDistanceToSurfaceMeshWithBvh branch from 8255499 to ec684c1 Compare January 20, 2024 18:51
@DamrongGuoy DamrongGuoy changed the title [geometry] Add CalcDistanceToSurfaceMeshWithBvh() [geometry] Accelerate initialization of compliant-hydroelastic nonconvex meshes Jan 23, 2024
@DamrongGuoy DamrongGuoy force-pushed the draft_CalcDistanceToSurfaceMeshWithBvh branch 4 times, most recently from c5bcf39 to ad830e9 Compare January 29, 2024 23:16
@DamrongGuoy DamrongGuoy marked this pull request as ready for review January 29, 2024 23:39
Copy link
Contributor Author

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

-(status: do not merge) -(status: do not review)

+@sherm1 for feature review, please.

Reviewable status: LGTM missing from assignee sherm1(platform), needs at least two assigned reviewers, labeled "do not merge", missing label for release notes (waiting on @DamrongGuoy)

@sherm1
Copy link
Member

sherm1 commented Jan 30, 2024

geometry/proximity/BUILD.bazel line 133 at r3 (raw file):

    deps = [
        ":distance_to_point_callback",
    ],

BTW I don't understand interface_deps vs deps so can't say for sure whether this is right or wrong. @jwnimmer-tri can you feature review just this change?

Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

+@jwnimmer-tri for feature review of just the BUILD.bazel change, please

Reviewed all commit messages.
Reviewable status: 1 unresolved discussion, LGTM missing from assignees jwnimmer-tri(platform),sherm1(platform), missing label for release notes (waiting on @DamrongGuoy)

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

:lgtm:

Reviewable status: 1 unresolved discussion, LGTM missing from assignee sherm1(platform), missing label for release notes (waiting on @DamrongGuoy)


geometry/proximity/BUILD.bazel line 133 at r3 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW I don't understand interface_deps vs deps so can't say for sure whether this is right or wrong. @jwnimmer-tri can you feature review just this change?

When a library gives "interface deps" vs "deps", the former lists things that can used by either *.h or *.cc files and the latter lists things that can only be used by *.cc files.

That suggests that ideally :geometric_transform should move from interface_deps to deps, since it's only used in the cc file.

In practice, that probably won't make any difference since anything that uses calc_distance_to_surface_mesh will almost certainly already depend on RotationMatrix one way or other.

Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Feature :lgtm: pending a few minor things

Reviewed 2 of 3 files at r2, 6 of 6 files at r3.
Reviewable status: 3 unresolved discussions, missing label for release notes (waiting on @DamrongGuoy)


geometry/proximity/calc_distance_to_surface_mesh.cc line 154 at r3 (raw file):

  unused(is_Q_on_edge_or_vertex);
  double signed_distance =
      grad_signed_distance_B.dot(p_BQ - closest_point_on_box_boundary_B);

BTW per f2f this is correct if the gradient vector is aligned with the p-closest vector. Might be worth saying something about that here because it wasn't obvious to me looking at the code.


geometry/proximity/volume_to_surface_mesh.h line 61 at r3 (raw file):

TriangleSurfaceMesh<T> ConvertVolumeToSurfaceMeshWithBoundaryVertices(
    const VolumeMesh<T>& volume,
    std::set<int>* return_boundary_vertices = nullptr);

minor: It is odd for a public API named "...WithBoundaryVertices" to have optional boundary vertices. I think you did that so you could use this function to implement the pre-existing no-boundary-vertices function above. A better approach would be to make a private method with an optional boundary vertices parameter, and then use that to implement both of the public methods.

Does this have to be public? If so, it should have documentation and a unit test.

@DamrongGuoy DamrongGuoy force-pushed the draft_CalcDistanceToSurfaceMeshWithBvh branch from ad830e9 to 785204d Compare January 31, 2024 00:29
Copy link
Contributor Author

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: missing label for release notes


geometry/proximity/BUILD.bazel line 133 at r3 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

When a library gives "interface deps" vs "deps", the former lists things that can used by either *.h or *.cc files and the latter lists things that can only be used by *.cc files.

That suggests that ideally :geometric_transform should move from interface_deps to deps, since it's only used in the cc file.

In practice, that probably won't make any difference since anything that uses calc_distance_to_surface_mesh will almost certainly already depend on RotationMatrix one way or other.

Thank you for your explanation. I moved :geometric_transform to deps.


geometry/proximity/calc_distance_to_surface_mesh.cc line 154 at r3 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW per f2f this is correct if the gradient vector is aligned with the p-closest vector. Might be worth saying something about that here because it wasn't obvious to me looking at the code.

Done. Thanks. I added a comment per f2f.


geometry/proximity/volume_to_surface_mesh.h line 61 at r3 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

minor: It is odd for a public API named "...WithBoundaryVertices" to have optional boundary vertices. I think you did that so you could use this function to implement the pre-existing no-boundary-vertices function above. A better approach would be to make a private method with an optional boundary vertices parameter, and then use that to implement both of the public methods.

Does this have to be public? If so, it should have documentation and a unit test.

Done. It's internal now. Thanks.

Copy link
Contributor Author

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

+@rpoyner-tri for platform review, please. Please let me know if it's too late in the day, and I'll find another reviewer.

Reviewable status: LGTM missing from assignee rpoyner-tri(platform), missing label for release notes (waiting on @DamrongGuoy)

@rpoyner-tri rpoyner-tri assigned sammy-tri and unassigned rpoyner-tri Jan 31, 2024
Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It's late. Passing the platform review buck ( -@rpoyner-tri ) to +@sammy-tri for Thursday-schedule review.

Reviewable status: LGTM missing from assignee sammy-tri(platform), missing label for release notes (waiting on @DamrongGuoy)

@jwnimmer-tri
Copy link
Collaborator

I'm on call for Thursday. I'll just do platform on this once since I'm already here.

@jwnimmer-tri jwnimmer-tri added the release notes: fix This pull request contains fixes (no new features) label Jan 31, 2024
Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

-@sammy-tri can skip this one.

+(release notes: fix)

Reviewable status: 1 unresolved discussion

a discussion (no related file):
Working

Needs platform review (me).


Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewed 5 of 5 files at r4, all commit messages.
Reviewable status: 2 unresolved discussions


geometry/proximity/volume_to_surface_mesh.h line 4 at r4 (raw file):

#include <array>
#include <optional>

BTW is this new include needed?

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Checkpoint.

Reviewed 1 of 6 files at r3, 2 of 5 files at r4, all commit messages.
Reviewable status: 6 unresolved discussions


geometry/proximity/calc_distance_to_surface_mesh.h line 12 at r4 (raw file):

/* Computes the shortest unsigned distance between the point p_WQ and any point
 on the surface mesh `mesh_W`. The returned valued is non-negative.

typo

Suggestion:

returned value is

geometry/proximity/calc_distance_to_surface_mesh.cc line 124 at r4 (raw file):

//  performance is an issue for CalcSquaredDistanceToTriangle().

double TraverseBvhForMinSquaredDistance(

See DamrongGuoy#6


geometry/proximity/calc_distance_to_surface_mesh.cc line 145 at r4 (raw file):

  const Vector3d box_half_width_B = node_W.bv().half_width();
  RigidTransformd X_WB = node_W.bv().pose();

nit Spurious copying?

(Fixed in my PR.)

Suggestion:

const RigidTransformd& X_WB = node_W.bv().pose();

geometry/proximity/calc_distance_to_surface_mesh.cc line 152 at r4 (raw file):

      point_distance::DistanceToPoint<double>::ComputeDistanceToBox<3>(
          box_half_width_B, p_BQ);
  unused(is_Q_on_edge_or_vertex);

BTW There might be a more typical / convenient shorthand available, if it works in our current version of C++. (In both Python and C++, a single underscore means "placeholder variable that I don't care about".)

(Fixed in my PR.)

Suggestion:

  const auto [closest_point_on_box_boundary_B, grad_signed_distance_B, _] =
      point_distance::DistanceToPoint<double>::ComputeDistanceToBox<3>(
          box_half_width_B, p_BQ);

@jwnimmer-tri
Copy link
Collaborator

Is the best way to observe the performance speed-up here just the tutorial notebook, or is there any more focused demo that I could look at?

@jwnimmer-tri
Copy link
Collaborator

Or perhaps more specifically -- do you have perf numbers (in release mode) for the speed-up attributable to the boundary_vertices plumbing? That one in particular adds a lot of code complexity and API plumbing, and I wonder how much it's actually accomplishing compared to just BVH alone?

Copy link
Contributor Author

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for asking. Perhaps you can use ModelVisualizer to load SDFormat/URDF files that use large VTK meshes to see the difference.

For example anzu master has:

anzu (master)$ time ./run --build '' //models:show models/home_kitchen/accessories/sweet_home_dish_drying_rack_wireframe.sdf 
real	0m35.166s
user	0m26.245s
sys	0m0.175s

This example is 18X faster (in user time, 26 seconds vs. 1.4 seconds) with this branch:

anzu (master)$ time ./run --build '' //models:show models/home_kitchen/accessories/sweet_home_dish_drying_rack_wireframe.sdf 
real	0m8.607s
user	0m1.406s
sys	0m0.163s

The VTK has 22k tetrahedra. It's on the large side of our asset.

$ grep CELLS bazel-bin/models/home_kitchen/accessories/sweet_home_dish_drying_rack_wireframe_low.vtk
CELLS 22213 88848

Other VTK files with a smaller number of tetrahedra will see less difference.

image.png

Reviewable status: 5 unresolved discussions


geometry/proximity/calc_distance_to_surface_mesh.h line 12 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

typo

Done. Thanks.

Copy link
Contributor Author

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

My explanation about the number of tetrahedra was misleading. We get excellent speed up for the drying rack wireframe because it has a high "surface-to-volume" ratio. The number of surface triangles is relatively large, i.e., thinner geometry will benefit more.

Reviewable status: 5 unresolved discussions

Copy link
Contributor Author

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

About boundary_vertices plumbing, I can do a test tomorrow. If a very thin object has the most vertices on the surface with very few interior vertices, then we should make a profit by skipping boundary vertices. I'll try to get a number tomorrow.

Reviewable status: 5 unresolved discussions

@jwnimmer-tri
Copy link
Collaborator

Thanks.

For loading the drying rack, on my computer I get:

  • 20.7 seconds with Drake master
  • 1.19 seconds with this PR merged up to Drake master
  • 1.56 seconds with this PR merged up to Drake master, with the boundary_vertices piece unhooked

So yes, the "zero pressure at boundary" does seem to matter (approx 370ms fasten for the case of loading the rack). We should keep the idea intact. I'll think about if we can make the code less cumbersome.

I'll post more comments inline in the pull request, later on.

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 10 unresolved discussions


geometry/proximity/deformable_contact_geometries.cc line 38 at r4 (raw file):

  for (int v = 0; v < num_vertices; ++v) {
    signed_distance.emplace_back(
        (boundary_vertices.count(v))

BTW Ditto here (refer to the below discussion on pressure field stuff in volume_to_surface_mesh). There's no reason to do O(log N) time lookups here. Just iterate over the boundary_vertices in order, in lockstep with int v. They are a strict subset of all v, and are seen in the same (monotonic) order.


geometry/proximity/volume_to_surface_mesh.h line 42 at r4 (raw file):

/*
 Implements the public API ConvertVolumeToSurfaceMesh() with optional return
 of the boundary vertices that we can use internally.

nit It's probably important for the docs to clarify which topology this returned integers are with reference to (they are volume->mesh() indices). They are not surface mesh indices. That might be obvious once you think about it, but I think it's worth spelling out directly; don't make people work for it.


geometry/proximity/volume_to_surface_mesh.cc line 129 at r4 (raw file):

  if (return_boundary_vertices != nullptr) {
    *return_boundary_vertices =
        std::set<int>(boundary_vertices.begin(), boundary_vertices.end());

Seeing std::set<int> in performance-sensitive code makes me suspicious, but it gets even worse after we look more closely. CollectUniqiueVertices already populates a std::set<int>, which it then copies to a std::vector<int> to return it, which we then copy back into a std::set<int>! To top it off, the only thing we do with this new set is call count on it, so having a stable iterator ordering for all of its elements didn't even matter anyway. But it's even worse than that. The thing we're looking (int v) is incrementing by one every time. There's no reason to do log-time lookups in the first place! We just need to keep a cursor over std::vector<int> boundary_vertices moving along in lockstep with int v in the for loop.

Here's the patch. It takes the Anzu demo from 1.19s to 1.15s on my computer, so proportionally within the mesh loading subsystem it's probably well over a 10% improvement.

diff --git a/geometry/proximity/volume_to_surface_mesh.h b/geometry/proximity/volume_to_surface_mesh.h
index 614816204c..c29d7d14e8 100644
--- a/geometry/proximity/volume_to_surface_mesh.h
+++ b/geometry/proximity/volume_to_surface_mesh.h
@@ -44,7 +44,7 @@ std::vector<int> CollectUniqueVertices(
 template <class T>
 TriangleSurfaceMesh<T> ConvertVolumeToSurfaceMeshWithBoundaryVertices(
     const VolumeMesh<T>& volume,
-    std::set<int>* return_boundary_vertices = nullptr);
+    std::vector<int>* return_boundary_vertices = nullptr);
 
 }  // namespace internal
 
diff --git a/geometry/proximity/make_mesh_field.cc b/geometry/proximity/make_mesh_field.cc
index 5e79c67fa1..2ea658b04b 100644
--- a/geometry/proximity/make_mesh_field.cc
+++ b/geometry/proximity/make_mesh_field.cc
@@ -21,7 +21,7 @@ namespace {
 
 template <typename T>
 TriangleSurfaceMesh<double> ConvertVolumeToSurfaceMeshDouble(
-    const VolumeMesh<T>& volume_mesh, std::set<int>* boundary_vertices) {
+    const VolumeMesh<T>& volume_mesh, std::vector<int>* boundary_vertices) {
   TriangleSurfaceMesh<T> surface =
       ConvertVolumeToSurfaceMeshWithBoundaryVertices(volume_mesh,
                                                      boundary_vertices);
@@ -46,7 +46,7 @@ VolumeMeshFieldLinear<T, T> MakeVolumeMeshPressureField(
     const VolumeMesh<T>* mesh_M, const T& hydroelastic_modulus) {
   DRAKE_DEMAND(hydroelastic_modulus > T(0));
   DRAKE_DEMAND(mesh_M != nullptr);
-  std::set<int> boundary_vertices;
+  std::vector<int> boundary_vertices;
   // The subscript _d is for the scalar type double.
   TriangleSurfaceMesh<double> surface_d =
       ConvertVolumeToSurfaceMeshDouble(*mesh_M, &boundary_vertices);
@@ -59,18 +59,20 @@ VolumeMeshFieldLinear<T, T> MakeVolumeMeshPressureField(
   T max_value(std::numeric_limits<double>::lowest());
   // First round, it's actually unsigned distance, not pressure values yet.
   const Bvh<Obb, TriangleSurfaceMesh<double>> bvh(surface_d);
-  int v = 0;
-  for (const Vector3<T>& p_MV : mesh_M->vertices()) {
-    T pressure(0);
-    if (!boundary_vertices.count(v)) {
-      Vector3<double> p_MV_d = ExtractDoubleOrThrow(p_MV);
-      pressure = internal::CalcDistanceToSurfaceMesh(p_MV_d, surface_d, bvh);
+  auto boundary_iter = boundary_vertices.begin();
+  for (int v = 0; v < ssize(mesh_M->vertices()); ++v) {
+    if (boundary_iter != boundary_vertices.end() && *boundary_iter == v) {
+      ++boundary_iter;
+      pressure_values.push_back(0);
+      continue;
     }
-    pressure_values.emplace_back(pressure);
+    const Vector3<T>& p_MV = mesh_M->vertex(v);
+    const Vector3<double> p_MV_d = ExtractDoubleOrThrow(p_MV);
+    T pressure = internal::CalcDistanceToSurfaceMesh(p_MV_d, surface_d, bvh);
+    pressure_values.push_back(pressure);
     if (max_value < pressure) {
       max_value = pressure;
     }
-    ++v;
   }
 
   if (max_value <= T(0)) {
diff --git a/geometry/proximity/volume_to_surface_mesh.cc b/geometry/proximity/volume_to_surface_mesh.cc
index be8e72bc3a..886582399c 100644
--- a/geometry/proximity/volume_to_surface_mesh.cc
+++ b/geometry/proximity/volume_to_surface_mesh.cc
@@ -118,16 +118,12 @@ std::vector<int> CollectUniqueVertices(
 
 template <class T>
 TriangleSurfaceMesh<T> ConvertVolumeToSurfaceMeshWithBoundaryVertices(
-    const VolumeMesh<T>& volume, std::set<int>* return_boundary_vertices) {
+    const VolumeMesh<T>& volume, std::vector<int>* return_boundary_vertices) {
   const std::vector<std::array<int, 3>> boundary_faces =
       internal::IdentifyBoundaryFaces(volume.tetrahedra());
 
-  const std::vector<int> boundary_vertices =
+  std::vector<int> boundary_vertices =
       internal::CollectUniqueVertices(boundary_faces);
-  if (return_boundary_vertices != nullptr) {
-    *return_boundary_vertices =
-        std::set<int>(boundary_vertices.begin(), boundary_vertices.end());
-  }
 
   std::vector<Vector3<T>> surface_vertices;
   surface_vertices.reserve(boundary_vertices.size());
@@ -148,6 +144,9 @@ TriangleSurfaceMesh<T> ConvertVolumeToSurfaceMeshWithBoundaryVertices(
                                volume_to_surface.at(face_vertices[2]));
   }
 
+  if (return_boundary_vertices != nullptr) {
+    *return_boundary_vertices = std::move(boundary_vertices);
+  }
   return TriangleSurfaceMesh<T>(std::move(surface_faces),
                                 std::move(surface_vertices));
 }

geometry/proximity/volume_to_surface_mesh.cc line 160 at r4 (raw file):

}  // namespace internal

DRAKE_DEFINE_FUNCTION_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_NONSYMBOLIC_SCALARS(

nit This stanza seems vestigial. The non-internal function is already inline in the header, so we don't need explicit instantiation on it in the cc file.

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

First pass complete.

Reviewed 2 of 6 files at r3, 3 of 5 files at r4.
Reviewable status: 12 unresolved discussions


geometry/proximity/volume_to_surface_mesh.h line 47 at r4 (raw file):

TriangleSurfaceMesh<T> ConvertVolumeToSurfaceMeshWithBoundaryVertices(
    const VolumeMesh<T>& volume,
    std::set<int>* return_boundary_vertices = nullptr);

nit This is the first instance of using return_ in the name of an output-only parameter. Across several examples like RenderEngine, CollisionFilter, etc. we've used _out as a suffix to indicate an output-only parameter. We should probably be consistent.

Suggestion:

boundary_vertices_out

geometry/proximity/test/calc_distance_to_surface_mesh_test.cc line 240 at r4 (raw file):

      CalcDistanceToSurfaceMesh(Vector3d::Zero(), surface_W, bvh_W);
  const double kHalfShortLength = kShortLength / 2;
  EXPECT_NEAR(distance_from_center, kHalfShortLength, 1e-10);

BTW To my eye, naming this intermediate quantity makes things less clear.

Suggestion:

  EXPECT_NEAR(distance_from_center, kShortLength / 2, 1e-10);

Copy link
Contributor Author

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 11 unresolved discussions, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)


geometry/proximity/calc_distance_to_surface_mesh.h line 12 at r4 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Done. Thanks.

Working. Somehow I missed the push.


geometry/proximity/calc_distance_to_surface_mesh.cc line 124 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

See DamrongGuoy#6

Done. Thank you very much for improving the code.

Copy link
Contributor Author

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 4 unresolved discussions, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)


geometry/proximity/calc_distance_to_surface_mesh.h line 12 at r4 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Working. Somehow I missed the push.

Done.


geometry/proximity/calc_distance_to_surface_mesh.cc line 145 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit Spurious copying?

(Fixed in my PR.)

Thanks!


geometry/proximity/calc_distance_to_surface_mesh.cc line 152 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

BTW There might be a more typical / convenient shorthand available, if it works in our current version of C++. (In both Python and C++, a single underscore means "placeholder variable that I don't care about".)

(Fixed in my PR.)

Thanks!


geometry/proximity/volume_to_surface_mesh.h line 4 at r4 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW is this new include needed?

Done. Removed. Thanks.


geometry/proximity/volume_to_surface_mesh.h line 42 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit It's probably important for the docs to clarify which topology this returned integers are with reference to (they are volume->mesh() indices). They are not surface mesh indices. That might be obvious once you think about it, but I think it's worth spelling out directly; don't make people work for it.

Done. Thanks.


geometry/proximity/volume_to_surface_mesh.h line 47 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit This is the first instance of using return_ in the name of an output-only parameter. Across several examples like RenderEngine, CollisionFilter, etc. we've used _out as a suffix to indicate an output-only parameter. We should probably be consistent.

Done. Thanks.


geometry/proximity/volume_to_surface_mesh.cc line 129 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

Seeing std::set<int> in performance-sensitive code makes me suspicious, but it gets even worse after we look more closely. CollectUniqiueVertices already populates a std::set<int>, which it then copies to a std::vector<int> to return it, which we then copy back into a std::set<int>! To top it off, the only thing we do with this new set is call count on it, so having a stable iterator ordering for all of its elements didn't even matter anyway. But it's even worse than that. The thing we're looking (int v) is incrementing by one every time. There's no reason to do log-time lookups in the first place! We just need to keep a cursor over std::vector<int> boundary_vertices moving along in lockstep with int v in the for loop.

Here's the patch. It takes the Anzu demo from 1.19s to 1.15s on my computer, so proportionally within the mesh loading subsystem it's probably well over a 10% improvement.

diff --git a/geometry/proximity/volume_to_surface_mesh.h b/geometry/proximity/volume_to_surface_mesh.h
index 614816204c..c29d7d14e8 100644
--- a/geometry/proximity/volume_to_surface_mesh.h
+++ b/geometry/proximity/volume_to_surface_mesh.h
@@ -44,7 +44,7 @@ std::vector<int> CollectUniqueVertices(
 template <class T>
 TriangleSurfaceMesh<T> ConvertVolumeToSurfaceMeshWithBoundaryVertices(
     const VolumeMesh<T>& volume,
-    std::set<int>* return_boundary_vertices = nullptr);
+    std::vector<int>* return_boundary_vertices = nullptr);
 
 }  // namespace internal
 
diff --git a/geometry/proximity/make_mesh_field.cc b/geometry/proximity/make_mesh_field.cc
index 5e79c67fa1..2ea658b04b 100644
--- a/geometry/proximity/make_mesh_field.cc
+++ b/geometry/proximity/make_mesh_field.cc
@@ -21,7 +21,7 @@ namespace {
 
 template <typename T>
 TriangleSurfaceMesh<double> ConvertVolumeToSurfaceMeshDouble(
-    const VolumeMesh<T>& volume_mesh, std::set<int>* boundary_vertices) {
+    const VolumeMesh<T>& volume_mesh, std::vector<int>* boundary_vertices) {
   TriangleSurfaceMesh<T> surface =
       ConvertVolumeToSurfaceMeshWithBoundaryVertices(volume_mesh,
                                                      boundary_vertices);
@@ -46,7 +46,7 @@ VolumeMeshFieldLinear<T, T> MakeVolumeMeshPressureField(
     const VolumeMesh<T>* mesh_M, const T& hydroelastic_modulus) {
   DRAKE_DEMAND(hydroelastic_modulus > T(0));
   DRAKE_DEMAND(mesh_M != nullptr);
-  std::set<int> boundary_vertices;
+  std::vector<int> boundary_vertices;
   // The subscript _d is for the scalar type double.
   TriangleSurfaceMesh<double> surface_d =
       ConvertVolumeToSurfaceMeshDouble(*mesh_M, &boundary_vertices);
@@ -59,18 +59,20 @@ VolumeMeshFieldLinear<T, T> MakeVolumeMeshPressureField(
   T max_value(std::numeric_limits<double>::lowest());
   // First round, it's actually unsigned distance, not pressure values yet.
   const Bvh<Obb, TriangleSurfaceMesh<double>> bvh(surface_d);
-  int v = 0;
-  for (const Vector3<T>& p_MV : mesh_M->vertices()) {
-    T pressure(0);
-    if (!boundary_vertices.count(v)) {
-      Vector3<double> p_MV_d = ExtractDoubleOrThrow(p_MV);
-      pressure = internal::CalcDistanceToSurfaceMesh(p_MV_d, surface_d, bvh);
+  auto boundary_iter = boundary_vertices.begin();
+  for (int v = 0; v < ssize(mesh_M->vertices()); ++v) {
+    if (boundary_iter != boundary_vertices.end() && *boundary_iter == v) {
+      ++boundary_iter;
+      pressure_values.push_back(0);
+      continue;
     }
-    pressure_values.emplace_back(pressure);
+    const Vector3<T>& p_MV = mesh_M->vertex(v);
+    const Vector3<double> p_MV_d = ExtractDoubleOrThrow(p_MV);
+    T pressure = internal::CalcDistanceToSurfaceMesh(p_MV_d, surface_d, bvh);
+    pressure_values.push_back(pressure);
     if (max_value < pressure) {
       max_value = pressure;
     }
-    ++v;
   }
 
   if (max_value <= T(0)) {
diff --git a/geometry/proximity/volume_to_surface_mesh.cc b/geometry/proximity/volume_to_surface_mesh.cc
index be8e72bc3a..886582399c 100644
--- a/geometry/proximity/volume_to_surface_mesh.cc
+++ b/geometry/proximity/volume_to_surface_mesh.cc
@@ -118,16 +118,12 @@ std::vector<int> CollectUniqueVertices(
 
 template <class T>
 TriangleSurfaceMesh<T> ConvertVolumeToSurfaceMeshWithBoundaryVertices(
-    const VolumeMesh<T>& volume, std::set<int>* return_boundary_vertices) {
+    const VolumeMesh<T>& volume, std::vector<int>* return_boundary_vertices) {
   const std::vector<std::array<int, 3>> boundary_faces =
       internal::IdentifyBoundaryFaces(volume.tetrahedra());
 
-  const std::vector<int> boundary_vertices =
+  std::vector<int> boundary_vertices =
       internal::CollectUniqueVertices(boundary_faces);
-  if (return_boundary_vertices != nullptr) {
-    *return_boundary_vertices =
-        std::set<int>(boundary_vertices.begin(), boundary_vertices.end());
-  }
 
   std::vector<Vector3<T>> surface_vertices;
   surface_vertices.reserve(boundary_vertices.size());
@@ -148,6 +144,9 @@ TriangleSurfaceMesh<T> ConvertVolumeToSurfaceMeshWithBoundaryVertices(
                                volume_to_surface.at(face_vertices[2]));
   }
 
+  if (return_boundary_vertices != nullptr) {
+    *return_boundary_vertices = std::move(boundary_vertices);
+  }
   return TriangleSurfaceMesh<T>(std::move(surface_faces),
                                 std::move(surface_vertices));
 }

Done. Thank you very much for the patch!


geometry/proximity/volume_to_surface_mesh.cc line 160 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit This stanza seems vestigial. The non-internal function is already inline in the header, so we don't need explicit instantiation on it in the cc file.

Done. Thanks.


geometry/proximity/test/calc_distance_to_surface_mesh_test.cc line 240 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

BTW To my eye, naming this intermediate quantity makes things less clear.

Done. Thanks.

Copy link
Contributor Author

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 4 unresolved discussions, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)


geometry/proximity/deformable_contact_geometries.cc line 38 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

BTW Ditto here (refer to the below discussion on pressure field stuff in volume_to_surface_mesh). There's no reason to do O(log N) time lookups here. Just iterate over the boundary_vertices in order, in lockstep with int v. They are a strict subset of all v, and are seen in the same (monotonic) order.

Working.

Copy link
Contributor Author

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 3 unresolved discussions, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)


geometry/proximity/deformable_contact_geometries.cc line 38 at r4 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Working.

Done.

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You should probably wait for another re-LGTM from @sherm1 before merging.

Reviewed 1 of 1 files at r5, 5 of 5 files at r6, 2 of 2 files at r7, 1 of 1 files at r8, all commit messages.
Reviewable status: 3 unresolved discussions, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @DamrongGuoy)

a discussion (no related file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

Working

Needs platform review (me).

:lgtm: platform.



geometry/proximity/deformable_contact_geometries.cc line 4 at r8 (raw file):

#include <algorithm>
#include <set>

nit Unused <set>.


geometry/proximity/make_mesh_field.cc line 5 at r6 (raw file):

#include <cmath>
#include <limits>
#include <set>

nit Unused <set>.


geometry/proximity/volume_to_surface_mesh.h line 4 at r8 (raw file):

#include <array>
#include <set>

nit Unused <set>.

…d deformables

- Use BVH in CalcDistanceToSurfaceMesh().
- Skip calling CalcDistanceToSurfaceMesh() on boundary vertices.
@DamrongGuoy DamrongGuoy force-pushed the draft_CalcDistanceToSurfaceMeshWithBvh branch from 18cb4d8 to 754119d Compare January 31, 2024 23:02
Copy link
Contributor Author

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'll wait for Sherm. Thanks.

Reviewable status: :shipit: complete! all discussions resolved, LGTM from assignees jwnimmer-tri(platform),sherm1(platform)


geometry/proximity/deformable_contact_geometries.cc line 4 at r8 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit Unused <set>.

Done. Thansk.


geometry/proximity/make_mesh_field.cc line 5 at r6 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit Unused <set>.

Done. Thanks.


geometry/proximity/volume_to_surface_mesh.h line 4 at r8 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit Unused <set>.

Done. Thanks.

Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Feature :lgtm: still!

Reviewed 1 of 1 files at r5, 3 of 5 files at r6, 3 of 3 files at r9, all commit messages.
Reviewable status: :shipit: complete! all discussions resolved, LGTM from assignees jwnimmer-tri(platform),sherm1(platform)

@sherm1 sherm1 merged commit 561ed79 into RobotLocomotion:master Feb 1, 2024
10 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
release notes: fix This pull request contains fixes (no new features)
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

5 participants