-
Notifications
You must be signed in to change notification settings - Fork 1.3k
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] Adds new CompliantCompliant intersection algorithm #22069
base: master
Are you sure you want to change the base?
[geometry] Adds new CompliantCompliant intersection algorithm #22069
Conversation
6848720
to
3a9a422
Compare
32652d3
to
d7a3133
Compare
d7a3133
to
9c7550c
Compare
2a60265
to
11621b4
Compare
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
+@DamrongGuoy for feature review, please. +@SeanCurtis-TRI because I'd like to have your eyes on this as well.
Reviewable status: LGTM missing from assignees DamrongGuoy,SeanCurtis-TRI(platform)
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I'm testing ComputeContactVolumes(). If things go well, I can start reviewing this PR tomorrow (Thu). Thanks for the nice job, Joe.
Reviewable status: LGTM missing from assignees SeanCurtis-TRI(platform),DamrongGuoy
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Generally looks good. I kibitzed on the core, but I like it.
Reviewed 3 of 5 files at r3.
Reviewable status: 14 unresolved discussions, LGTM missing from assignees SeanCurtis-TRI(platform),DamrongGuoy
geometry/proximity/mesh_plane_intersection.cc
line 169 at r3 (raw file):
polygon_vertices->push_back(p_MC); if (faces != nullptr) { faces->push_back(intersected_faces[e]);
Given that this is the only place this table is used, you can eliminate the earlier aliasing and just do:
faces->push_back(kMarchingTetsFaceTabel[intersection_code][e]);
This puts all of the face-related logic 100% conditional on whether we're returning faces.
geometry/proximity/field_intersection.cc
line 102 at r3 (raw file):
// Intersects the equilibrium plane with the tetrahedron element0. std::vector<Vector3<T>>* polygon_M = &(polygon_buffer[0]); std::vector<int>* faces = &(face_buffer[0]);
BTW I don't think faces
has much value as a local variable.
- By declaring it as a pointer, it's not as obvious that the invocation of
SliceTetrahedronWithPlane()
gets it as an output parameter (as opposed to explicitly passing&face_buffer[0]
. - It doesn't serve any unique purpose.
- It exists so it can then be passed along to
faces_in
. But thefaces_in
initialization would read better explicitly grabbing&face_buffer[0]
so that it has an obvious contract withfaces_out
. - Finally, you reassign
faces_in
back tofaces
to return. However, if you're always simply returning whatfaces_in
points at, why not just returnfaces_in
?
- It exists so it can then be passed along to
I guess there is some slight benefit in giving a name to the thing that gets cleared and then updated by SliceTetrahedronWithPlane()
, but it doesn't seem sufficient to justify its existence.
That said, not a defect (merely a passing comment on aesthetic options). You can completely ignore this.
(Same could be said about the polygon_M
. So, I realize you're just continuing what's there.)
geometry/proximity/field_intersection.cc
line 137 at r3 (raw file):
} // Walk the vertices checking for intersecting edges.
BTW It's unfortunate that we're paying this cost even if we do the original volume-volume algorithm. It feels like it artificially penalizes the old algorithm making performance comparisons between the two biased in favor of the new algorithm.
geometry/proximity/field_intersection.cc
line 140 at r3 (raw file):
for (int i = 0; i < size; ++i) { int j = (i + 1) % size; // If the edge out of vertex i is inside, include vertex i and face i
nit Clarification
Suggestion:
is at least partiall inside,
geometry/proximity/field_intersection.cc
line 148 at r3 (raw file):
// from element1 we insert face + 4, to indicate which element the edge // came from). if (distances[j] > 0) {
BTW In the most adversarial case, disatnces[i]
is exactly zero and distances[j]
is positive. In that case, the polygon will end up with a duplicated vertex. In a more practical case, if we're simply near zero, we'll introduce infinitesimally small edges into the polygon.
We should either put a note saying we're fine with that (numerically it shouldn't present a problem -- it only imparts downstream computation cost based on the illusory complexity of the polygon). Or we should do something about it. (One can imagine rejection on the new vertex if the squared distance to the previous vertex is less than some threshold (certainly, even micrometer-length edges don't strike me as useful).
Similar problem on the edges that get clipped coming back into the tet.
The above comment reflects my familiarity with this specific bit of code. I read a bit further and noted the RemoveNearlyDuplicateVertices()
call. Dur. That said, life would be better if we omitted the bad vertices in the first place, as function gets more expensive for every vertex we ultimately remove.
Still, this is probably something that should be kicked down the road.
geometry/proximity/field_intersection.cc
line 296 at r3 (raw file):
checked_pairs.insert(pair); const auto& [tet0, tet1] = pair;
BTW calling these tetM
and tetN
would help keep the semantics clearer. As it is, I had to spend some time convincing myself that pair<int, int>
was correct instead of SortedPair
. Associating the tet indices with mesh name would help in that regard.
geometry/proximity/field_intersection.cc
line 300 at r3 (raw file):
// they may or may not overlap. If they do not overlap and produce a contact // surface, we do not have to process any neighbors. Note: the initial set // of of candidate tets are all boundary tets, so their pressure ranges
nit typo
Suggestion:
// of candidate
geometry/proximity/field_intersection.cc
line 303 at r3 (raw file):
// necessarily intersect because they all contain 0 and are thus inserted // without checking range intersection. const std::vector<int> faces = CalcContactPolygon(
BTW You might consider changing this invocation so that you don't do a malloc for every tested tet pair.
geometry/proximity/field_intersection.cc
line 312 at r3 (raw file):
// Loop over all intersected faces. for (int i = 0; i < ssize(faces); ++i) { int face = faces[i];
nit: simpler
Suggestion:
for (int face : faces) {
geometry/proximity/field_intersection.cc
line 317 at r3 (raw file):
if (face < 4) { // The index of the neighbor of tet0 sharing the face with index face. int neighbor = mesh_topology_M.neighbor(tet0, face);
BTW Again, naming this neighborM
(along with tetM
and tetN
) would help reinforce the invariant on candidate_tetrahedra
.
geometry/proximity/field_intersection.cc
line 326 at r3 (raw file):
std::pair<int, int> neighbor_pair(neighbor, tet1); // If this candidate pair has already been checked, continue.
nit: This test on whether or not you insert something into the queue is redundant of the test you do on whether you do work pulling something out of the queue.
The queue starts unique (because it's a set drawn from the BVH intersection). So, you have a choice, either judiciously add a candidate pair to the queue or judiciously operate on an entry in the queue, but don't do both.
Opting for the latter seems to have several benefits:
- Fewer lines of code.
- The pair can be constructed in place in the queue.
- The "skip if visited" seems more inclusive and failsafe.
The downside is more churn on the queue size (but that's got limited impact as we only pay allocation costs as it gets larger.
geometry/proximity/field_intersection.h
line 74 at r3 (raw file):
the intersecting polygon expressed in frame M. Its unit normal vector in CCW winding order convention is in the same direction as the plane's normal vector.
nit: weird formatting. First paragraph unindented, second indented.
geometry/proximity/field_intersection.h
line 218 at r3 (raw file):
*/ void IntersectFields(const VolumeMeshFieldLinear<double, double>& field_M, const Bvh<Obb, TriangleSurfaceMesh<double>>& bvh_M,
BTW As the bvh_*
, tri_to_tet_M
, and mesh_topology_M
are all entangled types, it seems like they should be clustered within a struct. It would make the overloads more parallel.
It's not clear to me that any one of those three types has any value without the other two (that may not be 100% literally true, generally, but currently it appears to be the case).
geometry/proximity/field_intersection.h
line 302 at r3 (raw file):
@param[in] use_topology If true, uses the version of VolumeIntersector::IntersectFields() that makes use of the topology of the compliant geometries.
nit: technically the topology of the compliant geometries' surfaces.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
It took me a while to finished bug fixing and feature requests for ComputeContactVolumes() prototype. I can start reviewing this PR seriously now.
Reviewable status: 14 unresolved discussions, LGTM missing from assignees SeanCurtis-TRI(platform),DamrongGuoy
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Checkpoint. I have been reviewing the code for one or two hours. It's time to take a break.
Reviewable status: 21 unresolved discussions, LGTM missing from assignees SeanCurtis-TRI(platform),DamrongGuoy
geometry/proximity/field_intersection.cc
line 102 at r3 (raw file):
Previously, SeanCurtis-TRI (Sean Curtis) wrote…
BTW I don't think
faces
has much value as a local variable.
- By declaring it as a pointer, it's not as obvious that the invocation of
SliceTetrahedronWithPlane()
gets it as an output parameter (as opposed to explicitly passing&face_buffer[0]
.- It doesn't serve any unique purpose.
- It exists so it can then be passed along to
faces_in
. But thefaces_in
initialization would read better explicitly grabbing&face_buffer[0]
so that it has an obvious contract withfaces_out
.- Finally, you reassign
faces_in
back tofaces
to return. However, if you're always simply returning whatfaces_in
points at, why not just returnfaces_in
?I guess there is some slight benefit in giving a name to the thing that gets cleared and then updated by
SliceTetrahedronWithPlane()
, but it doesn't seem sufficient to justify its existence.That said, not a defect (merely a passing comment on aesthetic options). You can completely ignore this.
(Same could be said about the
polygon_M
. So, I realize you're just continuing what's there.)
Wow! I have just realized what we did in mesh_intersection
didn't translate to field_intersection
.
In mesh_intersection
, we use member variables as alternating buffers to avoid heap allocation like this:
drake/geometry/proximity/mesh_intersection.cc
Lines 185 to 188 in 303ae30
std::vector<Vector3<T>>* polygon_M = &(polygon_[0]); | |
// Initialize output polygon in M's frame from the triangular `face` of | |
// surface_N. | |
polygon_M->clear(); |
Here we use the function-local variables instead of member variables.
I agree it's not a defect unless the profiler can point to it. (It did in the mesh_intersection profile).
Please let me know if my comments aren't clear.
geometry/proximity/field_intersection.h
line 30 at r3 (raw file):
`element0` into the piecewise-linear field `field_M`, expressed in frame M. The second function f₁:ℝ³→ ℝ is specified by the tetrahedron index `element1` into the piecewise-linear field `field_N`, expressed in frame N.
Nothing to change here. I just give a historical account of naming.
When Sean and I worked on this code many years ago, we agreed that the frame notation: something_M
and something_N
means the same "something" expressed in two different frames. That's why we wrote field0_M
and field1_N
for field0
expressed in frame M and field1
expressed in frame N.
Obviously this convention is not clearly understood to everyone. I am ok with the new names field_M
and field_N
to mean two different fields expressed in fame M and frame N respectively. It's certainly not the same field
expressed in two different frames M and N.
Code quote:
The first linear function f₀:ℝ³→ ℝ is specified by the tetrahedron index
`element0` into the piecewise-linear field `field_M`, expressed in frame M.
The second function f₁:ℝ³→ ℝ is specified by the tetrahedron index
`element1` into the piecewise-linear field `field_N`, expressed in frame N.
geometry/proximity/field_intersection.h
line 39 at r3 (raw file):
n̂ points in the direction of increasing f₀ and decreasing f₁: n̂ = (∇f₀−∇f₁)/‖∇f₀−∇f₁‖
I'm not sure what to do with the subscripts 0 and 1 in all the unicode. Change them to fₘ
and fₙ
? I won't demand a change though.
Code quote:
n̂ = (∇f₀−∇f₁)/‖∇f₀−∇f₁‖
geometry/proximity/field_intersection.h
line 83 at r3 (raw file):
faces[i] ∈ [0, 3], then faces[i] is the index of a face of element0. If faces[i] ∈ [4, 7], then faces[i] - 4 is the index of a face of element1.
Blocking. I am sorry to say I don't understand the description of faces
. Could you please simplify or give examples? Mentioning some invariances would help. I think polygon_M.size() == faces.size()
, correct or not?
Perhaps we could help the audience by saying this invariance?
Each edge of the polygon is associated with one triangular face
of a tetrahedron because the polygon is the common intersection
of the equilibrium plane with the eight halfspaces from all faces of
the two tetrahedra. Some halfspaces are redundant and their
corresponding face indices do not show up in `faces`.
Code quote:
`faces` is a sequence of indices of faces of element0 and
element1 that intersect equilibrium_plane_M to produce
polygon_M. faces[i] contains the index of the face that
produced the edge (polygon_M[i], polygon_M[i+1]).
The values of `faces` are encoded to identify whether the
value corresponds to a face of element0 or element1. If
faces[i] ∈ [0, 3], then faces[i] is the index of a face of
element0. If faces[i] ∈ [4, 7], then faces[i] - 4 is the
index of a face of element1.
geometry/proximity/field_intersection.h
line 171 at r3 (raw file):
normal is in the direction of increasing the difference field0 - field1. Usually it is the direction of increasing field0 and decreasing field1.
Do 0 and 1 become M and N ?
Suggestion:
@param[out] surface_M The output mesh of the contact surface between
the two geometries expressed in frame M. The surface
normal is in the direction of increasing the
difference field_M - field_N. Usually it is the
direction of increasing field_M and decreasing field_N.
geometry/proximity/field_intersection.h
line 215 at r3 (raw file):
@param[out] e_M The scalar field on the contact surface, expressed in frame M. @note The output surface mesh may have duplicate vertices.
Since it's an overload, could we document only the extra parameters (or changed parameters) ? I put (up to 6X faster)
without any data. Please feel free to remove it or replace it with the number you got.
Suggestion:
/* Overload of the above version using a BVH of the surface triangles of
the volume meshes and neighbor traversal. It takes the same parameters
as the above version except that the BVHs are associated with the surface
triangles, and it requests these extra parameters to accelerate
computation (up to 6X faster):
@param[in] bvh_M The bounding volume hierarchy built on the surface mesh
of `field_M`.
@param[in] tri_to_tet_M A mapping from surface triangle indices in the
surface mesh of M to their corresponding tet
element indices in the volume mesh of M.
@param[in] mesh_topology_M A representation of the topology of the volume
mesh M. Used to access neighbor adjacencies.
@param[in] bvh_N The bounding volume hierarchy built on the surface mesh
of `field_N`.
@param[in] tri_to_tet_N A mapping from surface triangle indices in the
surface mesh of N to their corresponding tet
element indices in the volume mesh of N.
@param[in] mesh_topology_N A representation of the topology of the volume
mesh N. Used to access neighbor adjacencies.
geometry/proximity/field_intersection.cc
line 35 at r3 (raw file):
// p_NoMo_N = R_NM * p_NoMo_M = R_MN⁻¹ * (-p_MoNo_M) const Vector3<T> p_NMo = -(X_MN.rotation().matrix().transpose() * X_MN.translation());
I'm just curious. Have you tested that this alternative formula is faster? It's harder to understand, but I don't know how faster it becomes.
Code quote:
// p_NoMo_N = R_NM * p_NoMo_M = R_MN⁻¹ * (-p_MoNo_M)
const Vector3<T> p_NMo =
-(X_MN.rotation().matrix().transpose() * X_MN.translation());
geometry/proximity/field_intersection.cc
line 35 at r3 (raw file):
// p_NoMo_N = R_NM * p_NoMo_M = R_MN⁻¹ * (-p_MoNo_M) const Vector3<T> p_NMo = -(X_MN.rotation().matrix().transpose() * X_MN.translation());
BTW
Suggestion:
// p_NoMo_N = R_NM * p_NoMo_M = -(R_MN⁻¹ * p_MoNo_M)
const Vector3<T> p_NMo =
-(X_MN.rotation().matrix().transpose() * X_MN.translation());
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Another checkpoint after 2.5 more hours of reviewing the code. I'll continue on Monday.
Thank you for such an intricate work.
Reviewable status: 29 unresolved discussions, LGTM missing from assignees SeanCurtis-TRI(platform),DamrongGuoy
a discussion (no related file):
Respectfully blocking. I ran kcov and saw these pink lines lack coverage test in field_intersection.cc
. Please address them.
tools/dynamic_analysis/kcov_tool clean
bazel test --config=kcov geometry/proximity:field_intersection_test
tools/dynamic_analysis/kcov_tool merge bazel-kcov
ls `pwd`/bazel-kcov/index.html
a discussion (no related file):
BTW, the following pink line in hydroelastic_calculator.cc
lacks coverage test. It might preexist this PR? However, it's the compliant-compliant case, which is the target of this PR. CC: @rpoyner-tri
If I understand correctly, the pink line ensures reproducibility to the last bits of repeated runs. (Sometimes FCL calls f(A,B), sometimes calls f(B,A)).
rm -rf bazel-kcov
tools/dynamic_analysis/kcov_tool clean
bazel test --config=kcov geometry/proximity:hydroelastic_calculator_test
tools/dynamic_analysis/kcov_tool merge bazel-kcov
ls `pwd`/bazel-kcov/index.html
geometry/proximity/field_intersection.h
line 227 at r3 (raw file):
const math::RigidTransform<T>& X_MN, std::unique_ptr<MeshType>* surface_M, std::unique_ptr<FieldType>* e_M);
A random thought.Would you consider renaming this function instead of overloading? I might miss something. I haven't read the other part of the code.
I think having something like IntersectFields()
and IntersecFieldsWithTopology()
would be more convenient for profiling. I would be able to see, in the profile data, which function I was using.
Or if you are sure the IntersecFieldsWithTopology()
is always faster, I can accept that.
Code quote:
void IntersectFields(const VolumeMeshFieldLinear<double, double>& field_M,
const Bvh<Obb, TriangleSurfaceMesh<double>>& bvh_M,
const std::vector<TetFace>& tri_to_tet_M,
const VolumeMeshTopology& mesh_topology_M,
const VolumeMeshFieldLinear<double, double>& field_N,
const Bvh<Obb, TriangleSurfaceMesh<double>>& bvh_N,
const std::vector<TetFace>& tri_to_tet_N,
const VolumeMeshTopology& mesh_topology_N,
const math::RigidTransform<T>& X_MN,
std::unique_ptr<MeshType>* surface_M,
std::unique_ptr<FieldType>* e_M);
geometry/proximity/field_intersection.cc
line 106 at r3 (raw file):
faces->clear(); SliceTetrahedronWithPlane(element0, mesh0_M, equilibrium_plane_M, polygon_M, nullptr /* cut_edges */, faces);
Blocking. Is there a possibility that SliceTetrahedronWithPlane()
gives an empty polygon? We could exit early.
Suggestion:
SliceTetrahedronWithPlane(element0, mesh0_M, equilibrium_plane_M, polygon_M,
nullptr /* cut_edges */, faces);
RemoveNearlyDuplicateVertices(polygon_M);
// The plane didn't intersect the tetrahedron. Exit early.
if (polygon_M->size() < 3) return {};
geometry/proximity/field_intersection.cc
line 129 at r3 (raw file):
const Vector3<T> triangle_outward_normal_M = X_MN.rotation() * -mesh1_N.inward_normal(element1, face).cast<T>(); PosedHalfSpace<T> half_space_M(triangle_outward_normal_M, p_MA);
Optional. It took me a long time to convince myself that the indexing schemes of p_MVs[(face+1)%4]
and inward_normal(face)
are consistent. Perhaps this documentation would help?
// face 0 1 2 3
// p_MA p_MV1 p_MV2 p_MV3 p_MV0
// face vertices V3,V2,V1 V2,V3,V0 V3,V1,V0 V1,V2,V0
Code quote:
const Vector3<T>& p_MA = p_MVs[(face + 1) % 4];
const Vector3<T> triangle_outward_normal_M =
X_MN.rotation() * -mesh1_N.inward_normal(element1, face).cast<T>();
PosedHalfSpace<T> half_space_M(triangle_outward_normal_M, p_MA);
geometry/proximity/field_intersection.cc
line 163 at r3 (raw file):
out_M->push_back(wa * (*in_M)[i] + wb * (*in_M)[j]); faces_out->push_back((*faces_in)[i]); }
Is there a possibility that after this if () { if () {} } else { if () {}}
clause, the polygon becomes empty right in the first iteration? That would allow exiting early.
That's why the older code check for:
RemoveNearlyDuplicateVertices(out_M);
if (out_M->size() < 3) {
return {}; // Empty intersection; no contact here.
to exit early in every iteration. The new code, on the other hand, delays the check to the end.
I can also accept the reasoning that the extra iterations are cheap, so you don't have to change it.
Code quote:
if (distances[i] <= 0) {
out_M->push_back((*in_M)[i]);
faces_out->push_back((*faces_in)[i]);
// If vertex j is outside, we've discovered an intersection. Add the
// intersection point as well as "face" to the list of faces. (For faces
// from element1 we insert face + 4, to indicate which element the edge
// came from).
if (distances[j] > 0) {
const T wa = distances[j] / (distances[j] - distances[i]);
const T wb = T(1.0) - wa;
out_M->push_back(wa * (*in_M)[i] + wb * (*in_M)[j]);
faces_out->push_back(face + 4);
}
} else if (distances[j] <= 0) {
// Vertex i is outside, but vertex j is inside. We've discovered another
// intersection. Add the intersection point, this point is still on the
// edge created by faces_in[i], so include that face for the edge
// starting at the intersection point.
const T wa = distances[j] / (distances[j] - distances[i]);
const T wb = T(1.0) - wa;
out_M->push_back(wa * (*in_M)[i] + wb * (*in_M)[j]);
faces_out->push_back((*faces_in)[i]);
}
geometry/proximity/field_intersection.cc
line 164 at r3 (raw file):
faces_out->push_back((*faces_in)[i]); } }
Blocking please. Could you please factor out this block of code into a function? I understand it's doing something like ClipPolygonByHalfSpace()
with additional input and output. Otherwise, it's hard for me to understand and maintain the code. This way, we can have a separate unit test of this block, which could be sensitive to numerics and general positions.
Code quote:
const int size = ssize(*in_M);
for (int i = 0; i < size; ++i) {
distances[i] = half_space_M.CalcSignedDistance((*in_M)[i]);
}
// Walk the vertices checking for intersecting edges.
for (int i = 0; i < size; ++i) {
int j = (i + 1) % size;
// If the edge out of vertex i is inside, include vertex i and face i
if (distances[i] <= 0) {
out_M->push_back((*in_M)[i]);
faces_out->push_back((*faces_in)[i]);
// If vertex j is outside, we've discovered an intersection. Add the
// intersection point as well as "face" to the list of faces. (For faces
// from element1 we insert face + 4, to indicate which element the edge
// came from).
if (distances[j] > 0) {
const T wa = distances[j] / (distances[j] - distances[i]);
const T wb = T(1.0) - wa;
out_M->push_back(wa * (*in_M)[i] + wb * (*in_M)[j]);
faces_out->push_back(face + 4);
}
} else if (distances[j] <= 0) {
// Vertex i is outside, but vertex j is inside. We've discovered another
// intersection. Add the intersection point, this point is still on the
// edge created by faces_in[i], so include that face for the edge
// starting at the intersection point.
const T wa = distances[j] / (distances[j] - distances[i]);
const T wb = T(1.0) - wa;
out_M->push_back(wa * (*in_M)[i] + wb * (*in_M)[j]);
faces_out->push_back((*faces_in)[i]);
}
}
geometry/proximity/field_intersection.cc
line 174 at r3 (raw file):
RemoveNearlyDuplicateVertices(polygon_M); if (polygon_M->size() < 3) { // return std::make_pair(std::vector<Vector3<T>>(), *faces);
Blocking. Is this intentional?
Code quote:
// return std::make_pair(std::vector<Vector3<T>>(), *faces);
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewable status: 29 unresolved discussions, LGTM missing from assignees SeanCurtis-TRI(platform),DamrongGuoy
a discussion (no related file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
BTW, the following pink line in
hydroelastic_calculator.cc
lacks coverage test. It might preexist this PR? However, it's the compliant-compliant case, which is the target of this PR. CC: @rpoyner-triIf I understand correctly, the pink line ensures reproducibility to the last bits of repeated runs. (Sometimes FCL calls f(A,B), sometimes calls f(B,A)).
rm -rf bazel-kcov tools/dynamic_analysis/kcov_tool clean bazel test --config=kcov geometry/proximity:hydroelastic_calculator_test tools/dynamic_analysis/kcov_tool merge bazel-kcov ls `pwd`/bazel-kcov/index.html
The lapse predates this PR. Here's a patch:
diff --git a/geometry/proximity/test/hydroelastic_calculator_test.cc b/geometry/proximity/test/hydroelastic_calculator_test.cc
index 32fff1b1c0..d32618499a 100644
--- a/geometry/proximity/test/hydroelastic_calculator_test.cc
+++ b/geometry/proximity/test/hydroelastic_calculator_test.cc
@@ -592,6 +592,14 @@ TYPED_TEST(MaybeMakeContactSurfaceTests, BothCompliantNonHalfSpace) {
scene.calculator().MaybeMakeContactSurface(scene.id_A(), scene.id_B());
EXPECT_EQ(result, ContactSurfaceResult::kCalculated);
EXPECT_NE(surface, nullptr);
+
+ // Supplying ids in reversed order yields the same result, because the ids
+ // get put in order before constructing the surface.
+ auto [result_reversed, surface_reversed] =
+ scene.calculator().MaybeMakeContactSurface(scene.id_B(), scene.id_A());
+ EXPECT_EQ(result_reversed, ContactSurfaceResult::kCalculated);
+ EXPECT_NE(surface_reversed, nullptr);
+ EXPECT_EQ(surface->id_M(), surface_reversed->id_M());
}
TYPED_TEST(MaybeMakeContactSurfaceTests, BothHalfSpace) {
Feel free to include it here, or I can propose it separately if you like.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Another checkpoint. I'll go for lunch and try to finish it this afternoon. I have two more files to go.
Reviewed 1 of 10 files at r1, 2 of 6 files at r2, 2 of 5 files at r3, all commit messages.
Reviewable status: 30 unresolved discussions, LGTM missing from assignees SeanCurtis-TRI(platform),DamrongGuoy
geometry/proximity/field_intersection.cc
line 261 at r3 (raw file):
int tri0, int tri1) -> BvttCallbackResult { candidate_tetrahedra.emplace(tri_to_tet_M[tri0].tet_index, tri_to_tet_N[tri1].tet_index);
BTW, prevent mysterious memory issues by checking array bound (in debug mode), please.
Suggestion:
int tri0, int tri1) -> BvttCallbackResult {
DRAKE_ASSERT(0 <= tri0 < ssize(tri_to_tet_M));
DRAKE_ASSERT(0 <= tri1 < ssize(tri_to_tet_N));
candidate_tetrahedra.emplace(tri_to_tet_M[tri0].tet_index,
tri_to_tet_N[tri1].tet_index);
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Thank for both for the speedy reviews. @DamrongGuoy I'll work on the comments from the first few checkpoints now and get another revision in while you look at the tests.
BTW I just pushed a second commit with some updated tests to hopefully address the code coverage (and some additional correctness checking).
Reviewable status: 30 unresolved discussions, LGTM missing from assignees SeanCurtis-TRI(platform),DamrongGuoy, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Thank you for the diligent work @joemasterjohn .
with a few blocking comments that are open to negotiation.
Just reviewing the code took me totally 7 hours. I couldn't imagine how long it took Joe to develop the code. Thanks a lot!
Reviewed 2 of 6 files at r2, 1 of 1 files at r4, all commit messages.
Reviewable status: 36 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @joemasterjohn)
a discussion (no related file):
I'd like to praise that passing SoftMesh
instead of field
+ bvh
is a handy improvement. When I wrote the code the first time, I didn't have access to SoftMesh
. Thank you for the improvement.
geometry/proximity/test/field_intersection_test.cc
line 302 at r3 (raw file):
octahedron_N_ = SoftMesh(std::move(octahedron_mesh), std::move(octahedron_field)); }
Optional. I wonder whether there are C++ techniques to make SoftMesh box_M_
a const
here? Would something like this work? The downside is that it does an extra copy of const
variables.
Well...the more const
, the better?
VolumeIntersectorTest()
: box_mesh_M_(MakeBoxVolumeMeshWithMa<double>(box_)),
box_M_(
// Redundant copy of the box mesh to make `box_M_` a const variable.
std::make_unique<VolumeMesh<double>>(box_mesh_M_),
std::make_unique<VolumeMeshFieldLinear<double, double>>(
MakeBoxPressureField(box_, &box_mesh_M_,
kBoxElasitcModulus_))),
...
)
...
const VolumeMesh<double> box_mesh_M_;
const SoftMesh box_M_;
Ditto for the octahedron.
Code quote:
VolumeIntersectorTest() {
std::unique_ptr<VolumeMesh<double>> mesh =
std::make_unique<VolumeMesh<double>>(
MakeBoxVolumeMeshWithMa<double>(box_));
std::unique_ptr<VolumeMeshFieldLinear<double, double>> field =
std::make_unique<VolumeMeshFieldLinear<double, double>>(
MakeBoxPressureField<double>(box_, mesh.get(),
kBoxElasitcModulus_));
// Get a mesh of an octahedron from a sphere specification by
// specifying very coarse resolution hint.
std::unique_ptr<VolumeMesh<double>> octahedron_mesh =
std::make_unique<VolumeMesh<double>>(MakeSphereVolumeMesh<double>(
sphere_, 10 * sphere_.radius(),
TessellationStrategy::kSingleInteriorVertex));
std::unique_ptr<VolumeMeshFieldLinear<double, double>> octahedron_field =
std::make_unique<VolumeMeshFieldLinear<double, double>>(
MakeSpherePressureField<double>(sphere_, octahedron_mesh.get(),
kOctahedronElasticModulus_));
box_M_ = SoftMesh(std::move(mesh), std::move(field));
octahedron_N_ =
SoftMesh(std::move(octahedron_mesh), std::move(octahedron_field));
}
geometry/proximity/field_intersection.cc
line 236 at r4 (raw file):
template <class MeshBuilder, class BvType> void VolumeIntersector<MeshBuilder, BvType>::IntersectFields(
I'm fine with what we have right now. I just want to comment that the non-topology version of IntersectFields()
right before this one is only about 25 lines, and this topology-version of IntersectFields(VolumeMeshTopology)
is 4X longer, about 100 lines with about 75 lines in one while
loop.
In the future, we might want to refactor for easier direct testing of the logic in the while
loop. Right now we can't set up a simple unit test to verify the logic.
geometry/proximity/test/field_intersection_test.cc
line 336 at r4 (raw file):
// which they find candidate tetrahedra pairs from the two MeshFieldLinear // objects. Each end up calling CalcContactPolygon() with their candidate pairs. // Therefore, if we can verify that the each algorithm makes the same set of
BTW
Suggestion:
// Therefore, if we can verify that each algorithm makes the same set of
geometry/proximity/test/field_intersection_test.cc
line 558 at r4 (raw file):
kExpectGradientOrderOfMagnitude * Vector3d(1 / 3.0, -1 / 3.0, -1 / 3.0); EXPECT_TRUE(CompareMatrices(contact_patch_W->EvaluateGradE_N_W(0), expect_grad_e1_M, kGradientTolerance));
Optional. The actual values of the gradients are set by the {Tri,Poly}MeshBuilder
template parameter, so I won't demand checking those values here in IntersectCompliantVolume()
. They were tested already in MeshBuilder
(see contact_surface_utility_test.cc).
It is also true that 10 lines later we check the gradients again. That's a leftover when we refactor and created contact_surface_utility. I'll comment there as well.
geometry/proximity/test/field_intersection_test.cc
line 586 at r4 (raw file):
kExpectGradientOrderOfMagnitude * Vector3d(1 / 3.0, -1 / 3.0, -1 / 3.0); EXPECT_TRUE(CompareMatrices(contact_patch_W->EvaluateGradE_N_W(0), expect_grad_e1_M, kGradientTolerance));
This block was a leftover. They were tested in contact_surface_utility_test.cc already.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewable status: 35 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @joemasterjohn)
a discussion (no related file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
Respectfully blocking. I ran kcov and saw these pink lines lack coverage test in
field_intersection.cc
. Please address them.tools/dynamic_analysis/kcov_tool clean bazel test --config=kcov geometry/proximity:field_intersection_test tools/dynamic_analysis/kcov_tool merge bazel-kcov ls `pwd`/bazel-kcov/index.html
I re-ran kcov for r4
. The line volume_intersector.IntersectFields()
without use_topology is covered now. Thanks.
The three return {};
cases for CalcContactPolygon()
are still not covered, but I think they preexist this PR.
Satisfied now.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewable status: 36 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @joemasterjohn)
a discussion (no related file):
Temporary blocking.
I got up in the morning and something came to mind. The seeds of the search are the overlapping triangles' bounding boxes. What if the triangle intersection is empty, but we have non-empty tetrahedral field intersections? Sometimes the triangles and the tetrahedra may not agree (special cases). (Just like the face normals may not agree with the vertex normals in geometry with sharp features)
Please let me develop a unit test to confirm whether what I saw in my mind was hallucination or not.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewable status: 36 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @joemasterjohn)
a discussion (no related file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
Temporary blocking.
I got up in the morning and something came to mind. The seeds of the search are the overlapping triangles' bounding boxes. What if the triangle intersection is empty, but we have non-empty tetrahedral field intersections? Sometimes the triangles and the tetrahedra may not agree (special cases). (Just like the face normals may not agree with the vertex normals in geometry with sharp features)
Please let me develop a unit test to confirm whether what I saw in my mind was hallucination or not.
I confirm that the following diff will fail the test with nullptr dereferences. This special case is like submerging a spherical marble into a cup filled with water.
The entire marble is submerged in the water. There is no boundary triangle intersection but some tetrahedral fields do intersect.
The previous simple algorithm detected the contact surfaces. The newer faster algorithm did not detect this special case. Then, the unit test failed to compare the two results.
diff --git a/geometry/proximity/test/field_intersection_test.cc b/geometry/proximity/test/field_intersection_test.cc
index 57cddad5e7..f0c2378f9a 100644
--- a/geometry/proximity/test/field_intersection_test.cc
+++ b/geometry/proximity/test/field_intersection_test.cc
@@ -319,12 +319,13 @@ class VolumeIntersectorTest : public ::testing::Test {
DRAKE_DEMAND(octahedron_N_.mesh().num_elements() == 8);
}
- // Geometry 0 and its field.
- const Box box_{0.06, 0.10, 0.14}; // 6cm-thick compliant pad.
- const double kBoxElasitcModulus_{1.0e5};
+ // Geometry 0 and its field. Mimic a 10-cm cubical cup filled with water.
+ const Box box_{0.1, 0.1, 0.1};
+ const double kBoxElasitcModulus_{1.0e1};
SoftMesh box_M_;
- // Geometry 1 and its field.
+ // Geometry 1 and its field. Mimic a spherical marble dropped into the
+ // water cup.
const Sphere sphere_{0.03}; // 3cm-radius (6cm-diameter) finger tip.
const double kOctahedronElasticModulus_{1.0e5};
SoftMesh octahedron_N_;
@@ -360,7 +361,7 @@ bool ContactSurfacesAreEqual(
}
TEST_F(VolumeIntersectorTest, IntersectFields) {
- const RigidTransformd X_MN = RigidTransformd(0.03 * Vector3d::UnitX());
+ const RigidTransformd X_MN = RigidTransformd();
// Compute the contact surface using both algorithms provided by
// VolumeIntersector and check that they produce identical contact surfaces.
(pr_22069)*$ bazel test //geometry/proximity:field_intersection_test
[----------] 8 tests from VolumeIntersectorTest
[ RUN ] VolumeIntersectorTest.IntersectFields
geometry/proximity/test/field_intersection_test.cc:386: Failure
Expected: (surface_01_M[0].get()) != (nullptr), actual: NULL vs (nullptr)
Google Test trace:
geometry/proximity/test/field_intersection_test.cc:369: Use TriMeshBuilder.
geometry/proximity/test/field_intersection_test.cc:387: Failure
Expected: (surface_01_M[1].get()) != (nullptr), actual: NULL vs (nullptr)
Google Test trace:
geometry/proximity/test/field_intersection_test.cc:369: Use TriMeshBuilder.
================================================================================
INFO: Found 1 test target...
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewable status: 36 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @joemasterjohn)
a discussion (no related file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
I confirm that the following diff will fail the test with nullptr dereferences. This special case is like submerging a spherical marble into a cup filled with water.
The entire marble is submerged in the water. There is no boundary triangle intersection but some tetrahedral fields do intersect.
The previous simple algorithm detected the contact surfaces. The newer faster algorithm did not detect this special case. Then, the unit test failed to compare the two results.
diff --git a/geometry/proximity/test/field_intersection_test.cc b/geometry/proximity/test/field_intersection_test.cc index 57cddad5e7..f0c2378f9a 100644 --- a/geometry/proximity/test/field_intersection_test.cc +++ b/geometry/proximity/test/field_intersection_test.cc @@ -319,12 +319,13 @@ class VolumeIntersectorTest : public ::testing::Test { DRAKE_DEMAND(octahedron_N_.mesh().num_elements() == 8); } - // Geometry 0 and its field. - const Box box_{0.06, 0.10, 0.14}; // 6cm-thick compliant pad. - const double kBoxElasitcModulus_{1.0e5}; + // Geometry 0 and its field. Mimic a 10-cm cubical cup filled with water. + const Box box_{0.1, 0.1, 0.1}; + const double kBoxElasitcModulus_{1.0e1}; SoftMesh box_M_; - // Geometry 1 and its field. + // Geometry 1 and its field. Mimic a spherical marble dropped into the + // water cup. const Sphere sphere_{0.03}; // 3cm-radius (6cm-diameter) finger tip. const double kOctahedronElasticModulus_{1.0e5}; SoftMesh octahedron_N_; @@ -360,7 +361,7 @@ bool ContactSurfacesAreEqual( } TEST_F(VolumeIntersectorTest, IntersectFields) { - const RigidTransformd X_MN = RigidTransformd(0.03 * Vector3d::UnitX()); + const RigidTransformd X_MN = RigidTransformd(); // Compute the contact surface using both algorithms provided by // VolumeIntersector and check that they produce identical contact surfaces.(pr_22069)*$ bazel test //geometry/proximity:field_intersection_test [----------] 8 tests from VolumeIntersectorTest [ RUN ] VolumeIntersectorTest.IntersectFields geometry/proximity/test/field_intersection_test.cc:386: Failure Expected: (surface_01_M[0].get()) != (nullptr), actual: NULL vs (nullptr) Google Test trace: geometry/proximity/test/field_intersection_test.cc:369: Use TriMeshBuilder. geometry/proximity/test/field_intersection_test.cc:387: Failure Expected: (surface_01_M[1].get()) != (nullptr), actual: NULL vs (nullptr) Google Test trace: geometry/proximity/test/field_intersection_test.cc:369: Use TriMeshBuilder. ================================================================================ INFO: Found 1 test target...
It is a real blocking now. Since the new algorithm has serious troubles with special cases. May I ask for any one of the following:
- At least for now, we give users a choice to use which algorithm, or
- We keep the new algorithm internal for now until we can fix all special cases (there might be more), or
- Ability to switch the two algorithms at run-time pre-finalize, so we can compare them on more practical data sets.
I'd like to see this PR merge, so I'm open to any suggestions to unblock it.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewable status: 37 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @joemasterjohn)
a discussion (no related file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
It is a real blocking now. Since the new algorithm has serious troubles with special cases. May I ask for any one of the following:
- At least for now, we give users a choice to use which algorithm, or
- We keep the new algorithm internal for now until we can fix all special cases (there might be more), or
- Ability to switch the two algorithms at run-time pre-finalize, so we can compare them on more practical data sets.
I'd like to see this PR merge, so I'm open to any suggestions to unblock it.
I'm sorry again. I need to fix the above change to the unit test. Please stay tune. I didn't move the marble far anough.
geometry/proximity/test/field_intersection_test.cc
line 388 at r4 (raw file):
EXPECT_NE(surface_01_M[1].get(), nullptr); EXPECT_TRUE(ContactSurfacesAreEqual(intersector[0], *surface_01_M[0], intersector[1], *surface_01_M[1]));
Use ASSERT to exit early on nullptr. Otherwise, the test may dereference nullptr when we call ContactSurfacesAreEqual(...*surface_01_M[0], *surface_01_M[1]) and silently crashes.
Suggestion:
ASSERT_NE(surface_01_M[0].get(), nullptr);
ASSERT_NE(surface_01_M[1].get(), nullptr);
EXPECT_TRUE(ContactSurfacesAreEqual(intersector[0], *surface_01_M[0],
intersector[1], *surface_01_M[1]));
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewable status: 37 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @joemasterjohn)
a discussion (no related file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
I'm sorry again. I need to fix the above change to the unit test. Please stay tune. I didn't move the marble far anough.
I might be hallucinating. I still cannot come up with a good unit test. The above test that I made was invalid.
I need to send my son to school now. If this morning I can't come up with a good unit test, I'll retract this comment.
The main observation I had was that the older algorithm uses BVH of tetrahedra, and the newer algorithm uses BVH of triangles. What if BVH of tetrahedra found potential overlap, but BVH of triangles did not? I'm not sure anymore.
Sorry for the spam.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewable status: 37 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)
a discussion (no related file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
I might be hallucinating. I still cannot come up with a good unit test. The above test that I made was invalid.
I need to send my son to school now. If this morning I can't come up with a good unit test, I'll retract this comment.
The main observation I had was that the older algorithm uses BVH of tetrahedra, and the newer algorithm uses BVH of triangles. What if BVH of tetrahedra found potential overlap, but BVH of triangles did not? I'm not sure anymore.
Sorry for the spam.
I see, yeah that is an edge case I happened to overlook. However, I think it should be easy to detect. See if you like this argument:
- The boundaries of the two fields intersect spatially.
I argue that if this is the case, the algorithm will always succeed. Consider any two boundary tets whose boundary faces overlap spatially. Since they are boundary elements, their pressure ranges necessarily intersect (both contain 0 pressure). Thus, the equal-pressure surface is non-empty on the interior of the volume, and the computed polygon is non-empty. These polygons are the boundary polygons of the contact surface. Any polygon on the interior of the contact polygon must be path connected to some boundary polygon by continuity. We start at the boundary polygons and do an exhaustive search to find neighboring polygons. Thus, you can make an inductive argument that all polygons of the contact surface will be reached using this method.
Note: The one thing that might snag this argument is the polygons that we reject because the normal is not pointing in the general direction of the pressure gradient. Those do not become part of the output contact surface. But we still compute them and can traverse their neighbors even if rejected. I might have to make that modification to the algorithm for correctness.
- The boundaries of the two fields do not intersect spatially.
In this situation, there are two cases: either they do not intersect at all, or one of the geometries is entirely enclosed in the other. We can detect which case we're in with 2 point-to-surface mesh signed distance queries. Query the signed distance from any point on the interior to M to the boundary of N. If it is positive, then M is not entirely contained in N. Ditto for some point of N to the boundary of M. If both come out positive, neither is entirely contained within the other, so they must be disjoint. Otherwise, one of them is entirely contained in the other (we can't necessarily tell which one, but that doesn't matter much.
From there in my eyes there are maybe two reasonable things to do:
(1) Fallback to the old algorithm and compute the degenerate surface.
(2) Do nothing and throw an error/warning?
To me, once you're in that case, the contact surface doesn't mean anything physically anyway, so I would advocate for (2). I'd maybe like to hear @amcastro-tri and @SeanCurtis-TRI's opinions here.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewable status: 37 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @joemasterjohn)
a discussion (no related file):
Previously, joemasterjohn (Joe Masterjohn) wrote…
I see, yeah that is an edge case I happened to overlook. However, I think it should be easy to detect. See if you like this argument:
- The boundaries of the two fields intersect spatially.
I argue that if this is the case, the algorithm will always succeed. Consider any two boundary tets whose boundary faces overlap spatially. Since they are boundary elements, their pressure ranges necessarily intersect (both contain 0 pressure). Thus, the equal-pressure surface is non-empty on the interior of the volume, and the computed polygon is non-empty. These polygons are the boundary polygons of the contact surface. Any polygon on the interior of the contact polygon must be path connected to some boundary polygon by continuity. We start at the boundary polygons and do an exhaustive search to find neighboring polygons. Thus, you can make an inductive argument that all polygons of the contact surface will be reached using this method.
Note: The one thing that might snag this argument is the polygons that we reject because the normal is not pointing in the general direction of the pressure gradient. Those do not become part of the output contact surface. But we still compute them and can traverse their neighbors even if rejected. I might have to make that modification to the algorithm for correctness.
- The boundaries of the two fields do not intersect spatially.
In this situation, there are two cases: either they do not intersect at all, or one of the geometries is entirely enclosed in the other. We can detect which case we're in with 2 point-to-surface mesh signed distance queries. Query the signed distance from any point on the interior to M to the boundary of N. If it is positive, then M is not entirely contained in N. Ditto for some point of N to the boundary of M. If both come out positive, neither is entirely contained within the other, so they must be disjoint. Otherwise, one of them is entirely contained in the other (we can't necessarily tell which one, but that doesn't matter much.
From there in my eyes there are maybe two reasonable things to do:
(1) Fallback to the old algorithm and compute the degenerate surface.
(2) Do nothing and throw an error/warning?To me, once you're in that case, the contact surface doesn't mean anything physically anyway, so I would advocate for (2). I'd maybe like to hear @amcastro-tri and @SeanCurtis-TRI's opinions here.
I'm very bad at reading long text without pictures. I'll think about what you said carefully.
For this PR to merge, I'll add a unit test for the special cases, so we are aware of it. Can I push into your PR? Then, I'll be satisfied.
I think I got the unit test working now. I'm cleaning up and will post it.
The tricky part is that I can't use Box. Its mesh is so coarse that its triangles BVH always overlap with the sphere. This is because we store 3 triangles per leaf node in BVH as shown here.
Using a small sphere in a big sphere, I can create the unit test that the two versions of IntersecFields() do not agree.
I do agree this special cases may or may not be relevant to applications. (Do we want to model a small object submerging inside an aquarium?)
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewable status: 37 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @joemasterjohn)
a discussion (no related file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
I'm very bad at reading long text without pictures. I'll think about what you said carefully.
For this PR to merge, I'll add a unit test for the special cases, so we are aware of it. Can I push into your PR? Then, I'll be satisfied.
I think I got the unit test working now. I'm cleaning up and will post it.
The tricky part is that I can't use Box. Its mesh is so coarse that its triangles BVH always overlap with the sphere. This is because we store 3 triangles per leaf node in BVH as shown here.
Using a small sphere in a big sphere, I can create the unit test that the two versions of IntersecFields() do not agree.
I do agree this special cases may or may not be relevant to applications. (Do we want to model a small object submerging inside an aquarium?)
It's worth noting that anything completely submerged is going to be bad.
A small object fully penetrating into a big object is a version of pass through that would foil this algorithm. For rigid geometry, we don't require a single enclosed volume. One can also imagine a future in which the compliant geometry doesn't need it either. In that case, we can imagine small disjoint pieces of the geometry being completely submerged and only pick up contact from some of the pieces.
Ultimately, using only the boundary to detect contact when we can't guarantee contact includes the boundary will always be problematic.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewable status: 37 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @joemasterjohn)
a discussion (no related file):
Previously, SeanCurtis-TRI (Sean Curtis) wrote…
It's worth noting that anything completely submerged is going to be bad.
A small object fully penetrating into a big object is a version of pass through that would foil this algorithm. For rigid geometry, we don't require a single enclosed volume. One can also imagine a future in which the compliant geometry doesn't need it either. In that case, we can imagine small disjoint pieces of the geometry being completely submerged and only pick up contact from some of the pieces.
Ultimately, using only the boundary to detect contact when we can't guarantee contact includes the boundary will always be problematic.
This is the simple unit test. If we can add this unit test, I'll be happy. No need to change the actual code. That's for another day.
// This unit test suite shows that in special cases, the two versions of
// IntersectFields() give different results. One version can sense the
// contact, but the other version misses the contact.
//
// They are special cases that may or may not affect users depending on their
// applications.
//
class VolumeIntersectorTestSpecialCases : public ::testing::Test {
public:
VolumeIntersectorTestSpecialCases() {
std::unique_ptr<VolumeMesh<double>> big_mesh =
std::make_unique<VolumeMesh<double>>(MakeSphereVolumeMesh<double>(
big_sphere_, big_sphere_.radius(),
TessellationStrategy::kSingleInteriorVertex));
std::unique_ptr<VolumeMeshFieldLinear<double, double>> big_field =
std::make_unique<VolumeMeshFieldLinear<double, double>>(
MakeSpherePressureField<double>(big_sphere_, big_mesh.get(),
kElasticModulus_));
std::unique_ptr<VolumeMesh<double>> small_mesh =
std::make_unique<VolumeMesh<double>>(MakeSphereVolumeMesh<double>(
small_sphere_, small_sphere_.radius(),
TessellationStrategy::kSingleInteriorVertex));
std::unique_ptr<VolumeMeshFieldLinear<double, double>> small_field =
std::make_unique<VolumeMeshFieldLinear<double, double>>(
MakeSpherePressureField<double>(small_sphere_, small_mesh.get(),
kElasticModulus_));
big_sphere_M_ = SoftMesh(std::move(big_mesh), std::move(big_field));
small_sphere_N_ = SoftMesh(std::move(small_mesh), std::move(small_field));
}
protected:
void SetUp() override {
ASSERT_EQ(small_sphere_N_.mesh().num_elements(), 32);
}
// Geometry 0 and its field.
const Sphere big_sphere_{0.20};
SoftMesh big_sphere_M_;
// Geometry 1 and its field.
const Sphere small_sphere_{0.03};
SoftMesh small_sphere_N_;
const double kElasticModulus_{1.0e5};
};
TEST_F(VolumeIntersectorTestSpecialCases, IntersectFields) {
const RigidTransformd X_MN = RigidTransformd(0.10 * Vector3d::UnitX());
// Compute the contact surface using both algorithms provided by
// VolumeIntersector and check that they produce identical contact surfaces.
{
SCOPED_TRACE("Use PolyMeshBuilder.");
std::array<std::unique_ptr<PolygonSurfaceMesh<double>>, 2> surface_01_M;
std::array<std::unique_ptr<PolygonSurfaceMeshFieldLinear<double, double>>,
2>
e_MN_M;
std::array<VolumeIntersector<PolyMeshBuilder<double>, Obb>, 2> intersector;
intersector[0].IntersectFields(
big_sphere_M_.pressure(), big_sphere_M_.bvh(),
small_sphere_N_.pressure(), small_sphere_N_.bvh(), X_MN,
&surface_01_M[0], &e_MN_M[0]);
intersector[1].IntersectFields(
big_sphere_M_.pressure(), big_sphere_M_.surface_mesh_bvh(),
big_sphere_M_.tri_to_tet(), big_sphere_M_.mesh_topology(),
small_sphere_N_.pressure(), small_sphere_N_.surface_mesh_bvh(),
small_sphere_N_.tri_to_tet(), small_sphere_N_.mesh_topology(), X_MN,
&surface_01_M[1], &e_MN_M[1]);
// The first version of IntersectFields() can sense the contact.
EXPECT_NE(surface_01_M[0].get(), nullptr);
// The second version of IntersectFields() cannot.
EXPECT_EQ(surface_01_M[1].get(), nullptr);
}
}
@joemasterjohn could I push into this PR, please?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewable status: 37 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)
a discussion (no related file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
This is the simple unit test. If we can add this unit test, I'll be happy. No need to change the actual code. That's for another day.
// This unit test suite shows that in special cases, the two versions of // IntersectFields() give different results. One version can sense the // contact, but the other version misses the contact. // // They are special cases that may or may not affect users depending on their // applications. // class VolumeIntersectorTestSpecialCases : public ::testing::Test { public: VolumeIntersectorTestSpecialCases() { std::unique_ptr<VolumeMesh<double>> big_mesh = std::make_unique<VolumeMesh<double>>(MakeSphereVolumeMesh<double>( big_sphere_, big_sphere_.radius(), TessellationStrategy::kSingleInteriorVertex)); std::unique_ptr<VolumeMeshFieldLinear<double, double>> big_field = std::make_unique<VolumeMeshFieldLinear<double, double>>( MakeSpherePressureField<double>(big_sphere_, big_mesh.get(), kElasticModulus_)); std::unique_ptr<VolumeMesh<double>> small_mesh = std::make_unique<VolumeMesh<double>>(MakeSphereVolumeMesh<double>( small_sphere_, small_sphere_.radius(), TessellationStrategy::kSingleInteriorVertex)); std::unique_ptr<VolumeMeshFieldLinear<double, double>> small_field = std::make_unique<VolumeMeshFieldLinear<double, double>>( MakeSpherePressureField<double>(small_sphere_, small_mesh.get(), kElasticModulus_)); big_sphere_M_ = SoftMesh(std::move(big_mesh), std::move(big_field)); small_sphere_N_ = SoftMesh(std::move(small_mesh), std::move(small_field)); } protected: void SetUp() override { ASSERT_EQ(small_sphere_N_.mesh().num_elements(), 32); } // Geometry 0 and its field. const Sphere big_sphere_{0.20}; SoftMesh big_sphere_M_; // Geometry 1 and its field. const Sphere small_sphere_{0.03}; SoftMesh small_sphere_N_; const double kElasticModulus_{1.0e5}; }; TEST_F(VolumeIntersectorTestSpecialCases, IntersectFields) { const RigidTransformd X_MN = RigidTransformd(0.10 * Vector3d::UnitX()); // Compute the contact surface using both algorithms provided by // VolumeIntersector and check that they produce identical contact surfaces. { SCOPED_TRACE("Use PolyMeshBuilder."); std::array<std::unique_ptr<PolygonSurfaceMesh<double>>, 2> surface_01_M; std::array<std::unique_ptr<PolygonSurfaceMeshFieldLinear<double, double>>, 2> e_MN_M; std::array<VolumeIntersector<PolyMeshBuilder<double>, Obb>, 2> intersector; intersector[0].IntersectFields( big_sphere_M_.pressure(), big_sphere_M_.bvh(), small_sphere_N_.pressure(), small_sphere_N_.bvh(), X_MN, &surface_01_M[0], &e_MN_M[0]); intersector[1].IntersectFields( big_sphere_M_.pressure(), big_sphere_M_.surface_mesh_bvh(), big_sphere_M_.tri_to_tet(), big_sphere_M_.mesh_topology(), small_sphere_N_.pressure(), small_sphere_N_.surface_mesh_bvh(), small_sphere_N_.tri_to_tet(), small_sphere_N_.mesh_topology(), X_MN, &surface_01_M[1], &e_MN_M[1]); // The first version of IntersectFields() can sense the contact. EXPECT_NE(surface_01_M[0].get(), nullptr); // The second version of IntersectFields() cannot. EXPECT_EQ(surface_01_M[1].get(), nullptr); } }@joemasterjohn could I push into this PR, please?
@DamrongGuoy sure thing, feel free to push a commit.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewable status: 36 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @joemasterjohn)
a discussion (no related file):
Previously, joemasterjohn (Joe Masterjohn) wrote…
@DamrongGuoy sure thing, feel free to push a commit.
Satisifed now. I'll push the unit test later. Thanks!
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewed all commit messages.
Reviewable status: 37 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @joemasterjohn)
a discussion (no related file):
@joemasterjohn, I have pushed the test of special cases in r5. Thanks!
There was a problem hiding this 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, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @joemasterjohn)
geometry/proximity/field_intersection.h
line 30 at r3 (raw file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
Nothing to change here. I just give a historical account of naming.
When Sean and I worked on this code many years ago, we agreed that the frame notation:
something_M
andsomething_N
means the same "something" expressed in two different frames. That's why we wrotefield0_M
andfield1_N
forfield0
expressed in frame M andfield1
expressed in frame N.Obviously this convention is not clearly understood to everyone. I am ok with the new names
field_M
andfield_N
to mean two different fields expressed in fame M and frame N respectively. It's certainly not the samefield
expressed in two different frames M and N.
Ah ok. It's no problem to change it back, so I will. I wasn't even consistent myself in the name change.
geometry/proximity/field_intersection.h
line 39 at r3 (raw file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
I'm not sure what to do with the subscripts 0 and 1 in all the unicode. Change them to
fₘ
andfₙ
? I won't demand a change though.
Done. I've just gone back to the previous notation.
geometry/proximity/field_intersection.h
line 83 at r3 (raw file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
Blocking. I am sorry to say I don't understand the description of
faces
. Could you please simplify or give examples? Mentioning some invariances would help. I thinkpolygon_M.size() == faces.size()
, correct or not?Perhaps we could help the audience by saying this invariance?
Each edge of the polygon is associated with one triangular face of a tetrahedron because the polygon is the common intersection of the equilibrium plane with the eight halfspaces from all faces of the two tetrahedra. Some halfspaces are redundant and their corresponding face indices do not show up in `faces`.
Ok, I've incorporated your suggestions into the description. Sorry if it seems obscure, I was just trying to make the extra data compact.
geometry/proximity/field_intersection.h
line 171 at r3 (raw file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
Do 0 and 1 become M and N ?
I've gone back to the previous notation. I wasn't being consistent here before anyway.
geometry/proximity/field_intersection.h
line 215 at r3 (raw file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
Since it's an overload, could we document only the extra parameters (or changed parameters) ? I put
(up to 6X faster)
without any data. Please feel free to remove it or replace it with the number you got.
Done. I like that.
geometry/proximity/field_intersection.h
line 218 at r3 (raw file):
Previously, SeanCurtis-TRI (Sean Curtis) wrote…
BTW As the
bvh_*
,tri_to_tet_M
, andmesh_topology_M
are all entangled types, it seems like they should be clustered within a struct. It would make the overloads more parallel.It's not clear to me that any one of those three types has any value without the other two (that may not be 100% literally true, generally, but currently it appears to be the case).
I think the current state of affairs with these bare-bones versions of the data structures implies they only have this one use. But once the topology data structure is more fleshed out or we make more uses of the surface BVH I believe they will quickly become uncoupled.
geometry/proximity/field_intersection.h
line 227 at r3 (raw file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
A random thought.Would you consider renaming this function instead of overloading? I might miss something. I haven't read the other part of the code.
I think having something like
IntersectFields()
andIntersecFieldsWithTopology()
would be more convenient for profiling. I would be able to see, in the profile data, which function I was using.Or if you are sure the
IntersecFieldsWithTopology()
is always faster, I can accept that.
I might pass on the renaming for now. Since this is all internal code, we could easily change it with a small PR later if you feel strongly about it.
geometry/proximity/field_intersection.h
line 302 at r3 (raw file):
Previously, SeanCurtis-TRI (Sean Curtis) wrote…
nit: technically the topology of the compliant geometries' surfaces.
Done.
geometry/proximity/field_intersection.cc
line 35 at r3 (raw file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
I'm just curious. Have you tested that this alternative formula is faster? It's harder to understand, but I don't know how faster it becomes.
Not in a profiler, but I'm confident that it is doing less work. The previous expression required creating a temp RigidTransform
for the .inverse()
call. And then the full rigid transform operator *()
does a redundant matrix-vector product R_MN * p_MMo = R_MN * 0
, before adding the translation. Here I'm just computing the translation component of X_MN.inverse()
in place using only const refs and Eigen expressions.
geometry/proximity/field_intersection.cc
line 102 at r3 (raw file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
Wow! I have just realized what we did in
mesh_intersection
didn't translate tofield_intersection
.In
mesh_intersection
, we use member variables as alternating buffers to avoid heap allocation like this:
drake/geometry/proximity/mesh_intersection.cc
Lines 185 to 188 in 303ae30
std::vector<Vector3<T>>* polygon_M = &(polygon_[0]); // Initialize output polygon in M's frame from the triangular `face` of // surface_N. polygon_M->clear(); Here we use the function-local variables instead of member variables.
I agree it's not a defect unless the profiler can point to it. (It did in the mesh_intersection profile).
Please let me know if my comments aren't clear.
Ah I see. That might take a little bit of refactoring because IntersectTetrahedra()
is a free function. I might opt to leave it as is for now, profile after this lands, then go back over and optimize this more if needed.
geometry/proximity/field_intersection.cc
line 106 at r3 (raw file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
Blocking. Is there a possibility that
SliceTetrahedronWithPlane()
gives an empty polygon? We could exit early.
Done.
geometry/proximity/field_intersection.cc
line 129 at r3 (raw file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
Optional. It took me a long time to convince myself that the indexing schemes of
p_MVs[(face+1)%4]
andinward_normal(face)
are consistent. Perhaps this documentation would help?// face 0 1 2 3 // p_MA p_MV1 p_MV2 p_MV3 p_MV0 // face vertices V3,V2,V1 V2,V3,V0 V3,V1,V0 V1,V2,V0
Well the convention of inward_normal()
states that face i
is the face composed of the vertices of the tet that are not i
, so any of i+1, i+2, i+3 % 4
are equally good candidates for the point on the face: p_MA
. I've added a clarifying comment.
geometry/proximity/field_intersection.cc
line 137 at r3 (raw file):
Previously, SeanCurtis-TRI (Sean Curtis) wrote…
BTW It's unfortunate that we're paying this cost even if we do the original volume-volume algorithm. It feels like it artificially penalizes the old algorithm making performance comparisons between the two biased in favor of the new algorithm.
As far as I can tell, this is doing the same number of flops as ClipPolygonByHalfspace()
plus the extra push_back()
for the faces.
And for what it's worth, any of the A/B testing I did against the older algorithm used the version that is in master
now (none of these mods to the common functions of the two versions).
geometry/proximity/field_intersection.cc
line 148 at r3 (raw file):
Previously, SeanCurtis-TRI (Sean Curtis) wrote…
BTW In the most adversarial case,
disatnces[i]
is exactly zero anddistances[j]
is positive. In that case, the polygon will end up with a duplicated vertex. In a more practical case, if we're simply near zero, we'll introduce infinitesimally small edges into the polygon.We should either put a note saying we're fine with that (numerically it shouldn't present a problem -- it only imparts downstream computation cost based on the illusory complexity of the polygon). Or we should do something about it. (One can imagine rejection on the new vertex if the squared distance to the previous vertex is less than some threshold (certainly, even micrometer-length edges don't strike me as useful).
Similar problem on the edges that get clipped coming back into the tet.
The above comment reflects my familiarity with this specific bit of code. I read a bit further and noted the
RemoveNearlyDuplicateVertices()
call. Dur. That said, life would be better if we omitted the bad vertices in the first place, as function gets more expensive for every vertex we ultimately remove.Still, this is probably something that should be kicked down the road.
Thanks for the observation, I wasn't thinking too deeply about the numerics here and was just relying on the already vetted RemoveNearlyDuplicatedVertices()
to do it's job. But I agree, we could come back to take a look at this later to optimize.
geometry/proximity/field_intersection.cc
line 163 at r3 (raw file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
Is there a possibility that after this
if () { if () {} } else { if () {}}
clause, the polygon becomes empty right in the first iteration? That would allow exiting early.That's why the older code check for:
RemoveNearlyDuplicateVertices(out_M); if (out_M->size() < 3) { return {}; // Empty intersection; no contact here.to exit early in every iteration. The new code, on the other hand, delays the check to the end.
I can also accept the reasoning that the extra iterations are cheap, so you don't have to change it.
I'll argue that they're very cheap (cheaper than the function call and extra if ()). If the polygon is empty it is because distances[i] > 0
for all i
so none of these blocks will be entered. I did however add the early exit just below if one of the planes completely clips the polygon.
geometry/proximity/field_intersection.cc
line 164 at r3 (raw file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
Blocking please. Could you please factor out this block of code into a function? I understand it's doing something like
ClipPolygonByHalfSpace()
with additional input and output. Otherwise, it's hard for me to understand and maintain the code. This way, we can have a separate unit test of this block, which could be sensitive to numerics and general positions.
Hmm I might want to push back on this a bit. I wrote this inline intentionally because it's really deep in the inner loop and I wanted to avoid having to alias these already aliased double-buffers. It's a very specialized routine that I don't think has any use outside of this algorithm (unlike maybe ClipPolygonByHalfspace()
does. If you do feel strongly about the change though, I will make it.
geometry/proximity/field_intersection.cc
line 174 at r3 (raw file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
Blocking. Is this intentional?
Leftover from testing, removed.
geometry/proximity/field_intersection.cc
line 326 at r3 (raw file):
Previously, SeanCurtis-TRI (Sean Curtis) wrote…
nit: This test on whether or not you insert something into the queue is redundant of the test you do on whether you do work pulling something out of the queue.
The queue starts unique (because it's a set drawn from the BVH intersection). So, you have a choice, either judiciously add a candidate pair to the queue or judiciously operate on an entry in the queue, but don't do both.
Opting for the latter seems to have several benefits:
- Fewer lines of code.
- The pair can be constructed in place in the queue.
- The "skip if visited" seems more inclusive and failsafe.
The downside is more churn on the queue size (but that's got limited impact as we only pay allocation costs as it gets larger.
Since it's a BFS of the contact surface polygons, the queue has the potential to grow pretty large with redundant pairs. I'll opt to just rely on the judicious enqueuing to avoid the large queue size.
geometry/proximity/mesh_plane_intersection.cc
line 169 at r3 (raw file):
Previously, SeanCurtis-TRI (Sean Curtis) wrote…
Given that this is the only place this table is used, you can eliminate the earlier aliasing and just do:
faces->push_back(kMarchingTetsFaceTabel[intersection_code][e]);This puts all of the face-related logic 100% conditional on whether we're returning faces.
Done.
geometry/proximity/test/field_intersection_test.cc
line 302 at r3 (raw file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
Optional. I wonder whether there are C++ techniques to make
SoftMesh box_M_
aconst
here? Would something like this work? The downside is that it does an extra copy ofconst
variables.Well...the more
const
, the better?VolumeIntersectorTest() : box_mesh_M_(MakeBoxVolumeMeshWithMa<double>(box_)), box_M_( // Redundant copy of the box mesh to make `box_M_` a const variable. std::make_unique<VolumeMesh<double>>(box_mesh_M_), std::make_unique<VolumeMeshFieldLinear<double, double>>( MakeBoxPressureField(box_, &box_mesh_M_, kBoxElasitcModulus_))), ... ) ... const VolumeMesh<double> box_mesh_M_; const SoftMesh box_M_;Ditto for the octahedron.
I'm partially to not going the extra mile for the const, it's just a unit test. Maybe platform might say different though so I'll leave it up for debate.
I think the easier thing to do would be leave it non-const but make it private and then have the fixture provide const accessors to box_M()
and octahedron_N()
.
geometry/proximity/test/field_intersection_test.cc
line 388 at r4 (raw file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
Use ASSERT to exit early on nullptr. Otherwise, the test may dereference nullptr when we call ContactSurfacesAreEqual(...*surface_01_M[0], *surface_01_M[1]) and silently crashes.
Done.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Thanks for the thorough review, Damrong! And thanks for taking a look, Sean.
@SeanCurtis-TRI I know you're platform review Thursday. Would it be bad practice to have you serve as platform for this PR (since you partially feature review it)? If so maybe I should ask for a volunteer platform reviewer so I could merge it before break.
Reviewable status: 6 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @joemasterjohn)
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I believe I have resolved all the blocking comments to Satisfied
✔️ . Please let me know if I miss anyone. I'm hopeful this PR will merge soon.
I also talked to Rick Cory @rcory about the impact to the submersion test for assert validation. He said it's ok. He can make sure he doesn't dip manipulands into the tank too deep.
I have to send my son to school now. I'll try to be online again in 2 hours.
Reviewed 1 of 5 files at r3, 1 of 1 files at r5, all commit messages.
Reviewable status: 1 unresolved discussion, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @joemasterjohn)
geometry/proximity/field_intersection.h
line 227 at r3 (raw file):
Previously, joemasterjohn (Joe Masterjohn) wrote…
I might pass on the renaming for now. Since this is all internal code, we could easily change it with a small PR later if you feel strongly about it.
Fine with me. Thanks!
geometry/proximity/field_intersection.cc
line 35 at r3 (raw file):
Previously, joemasterjohn (Joe Masterjohn) wrote…
Not in a profiler, but I'm confident that it is doing less work. The previous expression required creating a temp
RigidTransform
for the.inverse()
call. And then the full rigid transformoperator *()
does a redundant matrix-vector productR_MN * p_MMo = R_MN * 0
, before adding the translation. Here I'm just computing the translation component ofX_MN.inverse()
in place using only const refs and Eigen expressions.
Satisfied. Thanks for the explanation.
geometry/proximity/field_intersection.cc
line 102 at r3 (raw file):
Previously, joemasterjohn (Joe Masterjohn) wrote…
Ah I see. That might take a little bit of refactoring because
IntersectTetrahedra()
is a free function. I might opt to leave it as is for now, profile after this lands, then go back over and optimize this more if needed.
Agreed. Satisfied. Thanks!
geometry/proximity/field_intersection.cc
line 106 at r3 (raw file):
Previously, joemasterjohn (Joe Masterjohn) wrote…
Done.
Thanks. Satisfied!
geometry/proximity/field_intersection.cc
line 164 at r3 (raw file):
Previously, joemasterjohn (Joe Masterjohn) wrote…
Hmm I might want to push back on this a bit. I wrote this inline intentionally because it's really deep in the inner loop and I wanted to avoid having to alias these already aliased double-buffers. It's a very specialized routine that I don't think has any use outside of this algorithm (unlike maybe
ClipPolygonByHalfspace()
does. If you do feel strongly about the change though, I will make it.
Fine with me. Thanks for the explanation. Satisfied.
geometry/proximity/test/field_intersection_test.cc
line 302 at r3 (raw file):
Previously, joemasterjohn (Joe Masterjohn) wrote…
I'm partially to not going the extra mile for the const, it's just a unit test. Maybe platform might say different though so I'll leave it up for debate.
I think the easier thing to do would be leave it non-const but make it private and then have the fixture provide const accessors to
box_M()
andoctahedron_N()
.
That's another good idea. Satisfied. No need to change it in this PR.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@joemasterjohn I can take it. Just make sure it passes CI.
Reviewable status: 1 unresolved discussion, LGTM missing from assignee SeanCurtis-TRI(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @joemasterjohn)
aa6d22c
to
4825f13
Compare
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@SeanCurtis-TRI got it thanks. CI was barking about a typo in a DRAKE_ASSERT
, should be all good now.
Reviewable status: 1 unresolved discussion, LGTM missing from assignee SeanCurtis-TRI(platform)
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewed 1 of 5 files at r3, 4 of 5 files at r6, 2 of 2 files at r7, all commit messages.
Reviewable status: 1 unresolved discussion, LGTM missing from assignee SeanCurtis-TRI(platform)
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I still need to look at the tests, but I wanted to publish the main review.
I'm going to suggest the following (I have a note below as well):
We do not turn on this new algorithm to be the default algorithm right before we all disappear for two weeks. For all of the obvious reasons, I think that would be ill advised.
Instead, leave the invocations to use the old algorithm and then when we come back, we can try turning it on and seeing what happens.
As this algorithm basically exacerbates pass through problems (now you don't have to pass the whole distance through, you just have to completely pass the surface), I think we should think a bit harder about what we want to say/do about it. This PR doesn't provide any warnings or guidance or recourse if encountered. Knowing that this isn't simply an acceleration, I think we should take that last step with some additional consideration.
-(release notes: fix) +(release notes: none) (When we turn it on or provide a switch in the future, we'll document the change.)
Reviewed 1 of 10 files at r1, 3 of 6 files at r2, 1 of 5 files at r3, 3 of 5 files at r6, 2 of 2 files at r7, all commit messages.
Reviewable status: 17 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform)
geometry/proximity/field_intersection.h
line 218 at r3 (raw file):
Previously, joemasterjohn (Joe Masterjohn) wrote…
I think the current state of affairs with these bare-bones versions of the data structures implies they only have this one use. But once the topology data structure is more fleshed out or we make more uses of the surface BVH I believe they will quickly become uncoupled.
I'd bet the opposite. I think we'd end up creating one Mesh to rule them all and all of this mesh-related data would become a part of it, supporting arbitrary queries.
I'm not going to ask you to make the change. But I'd like to plant a thought in your mind. As you agreed, in this PR, the three quantities are coupled (without exception). That relationship is best encoded with a single parameter and it further simplifies this function's interface.
The argument to not do that good thing, is predicated on an unclear property of some possible future state of the code. It makes much more sense if the change is concrete with some meaningfully anticipated timeline. But leaving today's code sloppy in hope that some time in the future it might pay off doesn't feel like a strong argument.
But again, I'm marking myself satisfied vis a vis this PR.
geometry/proximity/field_intersection.h
line 302 at r3 (raw file):
Previously, joemasterjohn (Joe Masterjohn) wrote…
Done.
You've got geometry's surfaces
- single geometry, multiple surfaces? My original suggestion was "geometries' surfaces" multiple geometries, multiple surfaces.
geometry/proximity/field_intersection.h
line 151 at r7 (raw file):
nit: The meaning/significance of this statement takes a hard right turn with the addition of the new implementation.
Before, it was a simple statement that this function was used for a specific purpose.
Now, you're saying those application purposes use both of these implementations, which is a bit misleading. With a newly-added choice, we need to reprhase the comment a bit:
Either of these functions can be used by Hydroelastics and deformables when the ...
geometry/proximity/field_intersection.h
line 156 at r7 (raw file):
BTW You don't have to change this, but because English sucks, this sentence is ambiguous. Two possible sets of grouping:
- (tetrahedral meshes with scalar fields) using a BVH of the volume elements of
- tetrahedral meshes with (scalar fields using a BVH of the volume elements) of
Alternate:
Creates the mesh and the scalar field on the contact surface between two tetrahedral meshes with scalar fields. This approach computes it by intersecting tetrahedra directly (accelerated with a BVH build on the tetrahedra).
Or some such thing. The goal would be to separate the gerund from the previous complex clause. It also does a good job of separating the semantics of the function (the first sentence) from details of implementation (the second sentence).
Code quote:
tetrahedral meshes with scalar fields using a BVH of the volume elements of
geometry/proximity/field_intersection.h
line 189 at r7 (raw file):
nit: "these" doesn't clearly refer to anything previous in the paragraph.
The parameters are similar to the previous overload with the following differences:
- The BVH is built on the volume mesh's surface mesh.
- We include additional data relating surface mesh to volume mesh and mesh topology.
Code quote:
these extra parameters
geometry/proximity/field_intersection.cc
line 102 at r3 (raw file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
Agreed. Satisfied. Thanks!
It seems the conversation finished on a different topic than I started.
Damrong's point seems to be pointing to heap allocation issues (difference between one allocation per constructor class vs per tet-tet invocation).
My point wasn't about heap access efficiency. It was about code clarity. I was positing that the symbols faces
and polygon_M
are either valueless (or possibly harmful).
For example, if everywhere you have faces
in this function you simply replaced it with &face_buffer[0]
I think the code is appreciably improved. Same for polygon_M
.
geometry/proximity/field_intersection.cc
line 137 at r3 (raw file):
Previously, joemasterjohn (Joe Masterjohn) wrote…
As far as I can tell, this is doing the same number of flops as
ClipPolygonByHalfspace()
plus the extrapush_back()
for the faces.And for what it's worth, any of the A/B testing I did against the older algorithm used the version that is in
master
now (none of these mods to the common functions of the two versions).
I've looked closer. I hadn't accounted for the fact that this is, in some sense, an unrolling of ClipPolygonByHalfSpace()
. Not literally so, but certainly true vis a vis order of magnitude.
geometry/proximity/mesh_plane_intersection.cc
line 65 at r7 (raw file):
std::array<int, 4>{-1, -1, -1, -1} /* 1111 */}; /* Each entry of kMarchingTetsEdgeTable stores a vector of face indices.
nit: typo
Suggestion:
kMarchingTetsFaceTable
geometry/proximity/mesh_plane_intersection.cc
line 71 at r7 (raw file):
to face {1, 2, 3} etc. The order of the indices is also constructed to follow to the order of the
nit grammar
Suggestion:
constructed to follow the order of the
geometry/proximity/mesh_plane_intersection.cc
line 72 at r7 (raw file):
The order of the indices is also constructed to follow to the order of the edges listed in the corresponding entry in kMarkingTetsEdgeTable. For instance:
I'm really unclear as the value of this discussion. Why is it important that the index ordering in some (complex) way correlate with the edge ordering? It doesn't seem that you use it in anyway.
The edge ordering makes sense because it allows you to walk the triangle in a particular order. But it's not apparent that the ordering here provides any value. If there's no value in the order, there's no value in the confusing documentation explaining it.
So, what am I missing?
geometry/proximity/mesh_plane_intersection.cc
line 147 at r7 (raw file):
for (int e = 0; e < 4; ++e) { const int edge_index = kMarchingTetsEdgeTable[intersection_code][e]; if (edge_index == -1) break;
nit: This line is very subtlely correct. It only works because for every -1 in the edge table, we have a -1 in the face table. (And conversely for values that are not -1.) We should put a note here explicitly acknowledging that expectation.
geometry/proximity/mesh_plane_intersection.cc
line 164 at r7 (raw file):
polygon_vertices->push_back(p_MC); if (faces != nullptr) { faces->push_back(kMarchingTetsFaceTable[intersection_code][e]);
nit e
is now very misleading. Originally, we only iterated through edges and e
as an index of edges seemed reasonable. However, it looks like we're somehow relating an edge with a face -- which we're not actually doing.
Now, we're really iterating though four candidate features (may be edges, may be faces). We're interested in the ith edge and/or the ith face. So, evolving the loop variable to reflect the evolution of the loop's body would be good. Perhaps a simple i
and a comment indicating that we have four candidate edges and four candidate faces, so we'll re-use i
for both purposes.
(Humorously, the two other words one might abbreviate, element and feature, both contract to the same thing as the misleading edge and face.)
geometry/proximity/test/field_intersection_test.cc
line 294 at r7 (raw file):
// This unit test suite shows that in special cases, the two versions of // IntersectFields() give different results. One version can sense the // contact, but the other version misses the contact.
BTW If I have a compliant box for a ground (so think big box), and I toss an object, depending on time step the small object could easily pass through the surface in a single time step. It's not a circumstance that would be difficult to achieve in a reasonable simulation scenario.
geometry/proximity/field_intersection.cc
line 103 at r7 (raw file):
std::vector<Vector3<T>>* polygon_M = &(polygon_buffer[0]); std::vector<int>* faces = &(face_buffer[0]); polygon_M->clear();
BTW Clearing these is functionally harmless, but it seems odd to clear a newly created vector. Surely it's already clear by construction. This may be another relic of copying this whole sale from a context in which these fields existed before this function's invocation.
geometry/proximity/field_intersection.cc
line 131 at r7 (raw file):
faces_out->clear(); // 'face' corresponds the the triangle formed by {0, 1, 2, 3} - {face}
nit: typo
Suggestion:
corresponds to the triangle
geometry/proximity/field_intersection.cc
line 275 at r7 (raw file):
return std::hash<int>()(p.first) ^ std::hash<int>()(p.second); }; std::unordered_set<std::pair<int, int>, decltype(pair_hash)> checked_pairs(
BTW This is painfully arcane. The use of decltype
, the magical "initial bin size" value of 8, etc.
Life would be simpler if you defined the hasher as its own thing:
namespace {
struct TetPairHasher final {
std::size_t operator()(const std::pair<int, int>& p) const {
return std::hash<int>()(p.first) ^ std::hash<int>()(p.second);
}
};
} // namespace
...
std::unordered_set<std::pair<int, int>, TetPairHasher> checked_pairs;
geometry/proximity/field_intersection.cc
line 285 at r7 (raw file):
std::pair<int, int> tet_pair(tri_to_tet_M[tri0].tet_index, tri_to_tet_N[tri1].tet_index); if (!checked_pairs.contains(tet_pair)) {
nit: This is really counterintuitive.
At this stage, you're collecting tet-pair candidates. Placing a pair in a construct called checked_pair
is a lie. Clearly, you haven't checked any pairs yet, so this collection should be empty.
I think the solution here is that the name of the set is wrong. It should be visited_pairs
and merely indicate that the pair has, at some point, been enqueued. It could even be enqueued_pairs
. Then what you're doing here makes much more sense. Now its purpose, its name, and its usage all align.
geometry/proximity/field_intersection.cc
line 510 at r7 (raw file):
.IntersectCompliantVolumes(id_M, compliant_M, X_WM, id_N, compliant_N, X_WN, &contact_surface_W, true /* use_topology */);
What's the design decision in turning this on by default when we know the algorithms aren't 100% equivalent?
I'd suggest leave it off for now, and we can turn it on when we come back from the xmas break.
geometry/proximity/field_intersection.h
line 148 at r7 (raw file):
algorithm for computing the contact surface of two pressure fields represented by two VolumeMeshFieldLinear objects. The implementations differ in their algorithmic details, but otherwise produce identical
nit: We know this statement isn't universally true. The "start-with-the-surfaces" algorithm will miss completely contact where surfaces don't intersect.
geometry/proximity/field_intersection.h
line 192 at r7 (raw file):
computation: @param[in] bvh_M The bounding volume hierarchy built on the surface mesh
btw: Meta note on this file. The formatting on the documentation is gradually becoming more erratic.
Previously, the parameter documentation kept all of the elaboration text justified to a shared left margin. That left margin has become more and more erratic.
It wasn't perfectly consistent before this PR, but it was far more unified (95% or so). Now, it's closer to 70%.
geometry/proximity/field_intersection.h
line 305 at r7 (raw file):
const math::RigidTransform<T>& X_WN, std::unique_ptr<ContactSurface<T>>* contact_surface_W, const bool use_topology = true);
nit: use_surfaces
seems much more direct and to the point. For example, I can think of ways of using topology information to improve the tet-vs-tet-based query. Therefore, using "topology" as a proxy for "surface contact" seems overly vague.
BTW There is something mildly odd about having two variables called |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Finished tests.
Reviewed 1 of 5 files at r6.
Reviewable status: 25 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform)
geometry/proximity/test/field_intersection_test.cc
line 429 at r7 (raw file):
nit: This statement doesn't seem correct.
The two algorithms are not guaranteed to make "the same set of calls to CalcContactPolygon()". The two approaches will doubtlessly produce different sets of candidate-test pairs. One produces pairs based on overlap of tet BVs and the other produces pairs by starting with the surface and walking the topology. The odds that those ever produce the same candidate sets is close to zero.
This test is trying to infer contact surface equality by doing a bunch of int comparisons. That's great. I think the more accurate characterization would be something like this:
Rather than comparing contact surfaces directly -- which is cumbersome because we have to handle equivalent topology variants and floating point issues -- we infer equivalency by looking at the build history. The intersector stores the pair of test which produce each element in the contact surface mesh. We'll simply confirm that the two sets tet-pairs match (and safely assume that they would produce the same surface).
Code quote:
// Therefore, if we can verify that each algorithm makes the same set of
// calls to CalcContactPolygon(), then the computed surfaces must be equivalent
geometry/proximity/test/field_intersection_test.cc
line 535 at r7 (raw file):
nit: The documentation at the top of this test says:
Smoke tests that AutoDiffXd can build.
As smoke tests go, just checking for non-null results seems sufficient (maybe even more than the documentation promises). Either way, we don't actually need to test for surface equality
Same below..
geometry/proximity/test/field_intersection_test.cc
line 248 at r7 (raw file):
// the faces is not strictly important. What is important is that all 4 faces // of each tetrahedra appear, and that (by construction) the edges alternate // intersection with a face of tet0 and a face of tet1.
BTW Related to my note in field_intersection.cc
. If that comment is correct about how much the relationship between face and edge encoding matters (not at all), then this part of the test is likewise unimportant.
Code quote:
// of each tetrahedra appear, and that (by construction) the edges alternate
// intersection with a face of tet0 and a face of tet1.
geometry/proximity/test/field_intersection_test.cc
line 290 at r7 (raw file):
} // Special cases that we may or may not care.
This "special case" test spans 100 lines. It can be expressed far more concisely. The introduction of a ::testing::Test
class introduces cost with no value because we only produce a single test from that test class. So, we might as well flatten it into one succinct test.
// The tet-based and tri-based algorithms will generally produce the same
// results. The exception is if one mesh is completely within the other (such
// that their surfaces don't intersect). In that case, the tri-based algorithm
// will incorrectly report no contact. This test quantifies that difference.
// Note: this is not a desirable behavior.
GTEST_TEST(VolumeIntersectionTest, FullyPenetrated) {
auto make_ball = [](double radius) {
const Sphere ball(radius);
auto mesh =
std::make_unique<VolumeMesh<double>>(MakeSphereVolumeMesh<double>(
ball, radius, TessellationStrategy::kSingleInteriorVertex));
auto field = std::make_unique<VolumeMeshFieldLinear<double, double>>(
MakeSpherePressureField<double>(ball, mesh.get(), 1e5));
return SoftMesh(std::move(mesh), std::move(field));
};
SoftMesh big_sphere_M = make_ball(1.0);
SoftMesh small_sphere_N = make_ball(1.0 / 8.0);
// Place the small sphere well within the big sphere, without surfaces
// touching.
const RigidTransformd X_MN(0.5 * Vector3d::UnitX());
std::array<std::unique_ptr<PolygonSurfaceMesh<double>>, 2> surface_01_M;
std::array<std::unique_ptr<PolygonSurfaceMeshFieldLinear<double, double>>, 2>
e_MN_M;
VolumeIntersector<PolyMeshBuilder<double>, Obb>().IntersectFields(
big_sphere_M.pressure(), big_sphere_M.bvh(), small_sphere_N.pressure(),
small_sphere_N.bvh(), X_MN, &surface_01_M[0], &e_MN_M[0]);
VolumeIntersector<PolyMeshBuilder<double>, Obb>().IntersectFields(
big_sphere_M.pressure(), big_sphere_M.surface_mesh_bvh(),
big_sphere_M.tri_to_tet(), big_sphere_M.mesh_topology(),
small_sphere_N.pressure(), small_sphere_N.surface_mesh_bvh(),
small_sphere_N.tri_to_tet(), small_sphere_N.mesh_topology(), X_MN,
&surface_01_M[1], &e_MN_M[1]);
// Index 0 only uses tets.
EXPECT_NE(surface_01_M[0].get(), nullptr);
// Index 1 depends on intersection at the surface.
EXPECT_EQ(surface_01_M[1].get(), nullptr);
}
geometry/proximity/test/field_intersection_test.cc
line 348 at r7 (raw file):
// be an interesting case for users. // // The penetration is deep enough that the two BVHs of the two surface
BTW This case is not about what the BVHs do or don't do. It's strictly about the fact that there are no intersecting triangles. Whether the BVHs produce triangle candidates is an incidental detail compared to whether or not triangles intersect.
geometry/proximity/test/field_intersection_test.cc
line 356 at r7 (raw file):
// surfaces: an empty one and a non-empty one. { SCOPED_TRACE("Use PolyMeshBuilder.");
BTW Throughout these testsSCOPED_TRACE
is misused. The best time to use it if if an EXPECT_FOO
line number insufficiently tells you what test is failing, such as if it appears in a for loop or in a shared function called by multiple times. Putting it in scope with the actual test values and test assertions provides no value.
geometry/proximity/test/field_intersection_test.cc
line 443 at r7 (raw file):
} std::multiset<std::pair<int, int>> set_A, set_B;
nit: This being a multiset
seems highly suspicious. I assume you're doing this because you're using this to test equivalence between triangluated contact surfaces (where one tet pair can produce multiple triangles). This should be clear.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewable status: 25 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform)
geometry/proximity/test/field_intersection_test.cc
line 290 at r7 (raw file):
Previously, SeanCurtis-TRI (Sean Curtis) wrote…
This "special case" test spans 100 lines. It can be expressed far more concisely. The introduction of a
::testing::Test
class introduces cost with no value because we only produce a single test from that test class. So, we might as well flatten it into one succinct test.// The tet-based and tri-based algorithms will generally produce the same // results. The exception is if one mesh is completely within the other (such // that their surfaces don't intersect). In that case, the tri-based algorithm // will incorrectly report no contact. This test quantifies that difference. // Note: this is not a desirable behavior. GTEST_TEST(VolumeIntersectionTest, FullyPenetrated) { auto make_ball = [](double radius) { const Sphere ball(radius); auto mesh = std::make_unique<VolumeMesh<double>>(MakeSphereVolumeMesh<double>( ball, radius, TessellationStrategy::kSingleInteriorVertex)); auto field = std::make_unique<VolumeMeshFieldLinear<double, double>>( MakeSpherePressureField<double>(ball, mesh.get(), 1e5)); return SoftMesh(std::move(mesh), std::move(field)); }; SoftMesh big_sphere_M = make_ball(1.0); SoftMesh small_sphere_N = make_ball(1.0 / 8.0); // Place the small sphere well within the big sphere, without surfaces // touching. const RigidTransformd X_MN(0.5 * Vector3d::UnitX()); std::array<std::unique_ptr<PolygonSurfaceMesh<double>>, 2> surface_01_M; std::array<std::unique_ptr<PolygonSurfaceMeshFieldLinear<double, double>>, 2> e_MN_M; VolumeIntersector<PolyMeshBuilder<double>, Obb>().IntersectFields( big_sphere_M.pressure(), big_sphere_M.bvh(), small_sphere_N.pressure(), small_sphere_N.bvh(), X_MN, &surface_01_M[0], &e_MN_M[0]); VolumeIntersector<PolyMeshBuilder<double>, Obb>().IntersectFields( big_sphere_M.pressure(), big_sphere_M.surface_mesh_bvh(), big_sphere_M.tri_to_tet(), big_sphere_M.mesh_topology(), small_sphere_N.pressure(), small_sphere_N.surface_mesh_bvh(), small_sphere_N.tri_to_tet(), small_sphere_N.mesh_topology(), X_MN, &surface_01_M[1], &e_MN_M[1]); // Index 0 only uses tets. EXPECT_NE(surface_01_M[0].get(), nullptr); // Index 1 depends on intersection at the surface. EXPECT_EQ(surface_01_M[1].get(), nullptr); }
You might want to mention that Box may not do it. I spent an hour or two figuring that the Box's 12-triangle mesh, with 3 triangles per BVH leaf node, can always create a non-empty seed. That's why I switched to sphere-in-sphere instead of sphere-in-box. Well...if it's too detailed, please feel free to ignore my comment.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewable status: 26 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform)
a discussion (no related file):
Random thought on what happens if volumes intersect but not surfaces. While I was pondering the problem, this idea came to mind. It is a possible heuristic to limit/mitigate the risk of us tripping over that. I'm sharing it not necessarily because it is the answer, but to throw out some ideas in hopes that someone can take it and run with it.
Consider the two OBBs of the two surface meshes. And by that, I mean the root OBBs of the two BVHs. If you measure the volume of the intersection of those boxes, the greatest possible volume is equal to that of the smaller OBB. Imagine for a moment that we could compute the volume of two OBBs intersection and normalize it by the volume of the smaller OBBs. We'll end up with an "overlap" score lying in the range [0, 1]. We could use this overlap score in one of two ways:
- We attempt to do the surface-surface algorithm. If we come back with nothing and the overlap score is 1.0, we fallback to the tet-tet algorithm.
- We compute the overlap score and for any score above some empirically determined threshold, we simply call the tet-tet algorithm.
Option (1) would give a false sense of security. On the one hand if there's overlap, we're guaranteed to find some overlap. But we're not guaranteed to find all the overlap. (This is an esoteric case where we have a single compliant geometry comprised of multiple disjoint "blobs". Not something we much of today but could see in the future).
Option (2) would probably produce the more reliable results. Essentially, we could say if the penetration is above 50% of the smaller one, we should default to tets because so much penetration is suggestive of possible traps. We'd generally assume that for any reasonable simulation with high stiffness, we wouldn't expect to see that much penetration, so we wouldn't trip the failsafe option, but it would be an excellent backgrop.
We certainly don't have to have the solution for this PR. But I think it behooves us to find some way to make the algorithm more robust. It's to bad that the BVHs aren't axis aligned, because that makes the intersecting volume trivial. I'm going to think about computing/estimating the volume of intersection between OBBs.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reviewable status: 26 unresolved discussions, LGTM missing from assignee SeanCurtis-TRI(platform)
geometry/proximity/test/field_intersection_test.cc
line 290 at r7 (raw file):
Previously, DamrongGuoy (Damrong Guoy) wrote…
You might want to mention that Box may not do it. I spent an hour or two figuring that the Box's 12-triangle mesh, with 3 triangles per BVH leaf node, can always create a non-empty seed. That's why I switched to sphere-in-sphere instead of sphere-in-box. Well...if it's too detailed, please feel free to ignore my comment.
I'm not sure what you mean. In my mind, the issues is simple: any time one surface mesh is completely embedded in another mesh, without surface intersections, this test would pass. It doesn't matter if they're spheres, boxes, or arbitrary non-convex shapes.
You seem to be alluding to some subtlety that I'm missing -- you're good at finding those corner cases. Can you help me see it?
Towards #21744.
Introduces the new compliant/compliant intersection algorithm and connects it to the contact surface query.
The algorithm itself resides in
VolumeIntersector::IntersectFields()
but you'll see changes elsewhere (VolumeIntersector::IntersectTetrahedra()
,SliceTetrahedronWithPlane()
) for the necessary bookkeeping modifications.This change is