Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Performance optimization for supportConvex #488

Conversation

SeanCurtis-TRI
Copy link
Contributor

@SeanCurtis-TRI SeanCurtis-TRI commented Aug 4, 2020

The original implementation of supportConvex did a linear search across all vertices. This makes the Convex mesh smarter to make the search for the support vertex cheaper.

  • It builds an adjacency graph on all vertices upon construction.
  • It introduces the method findExtremeVertex method which does a walk along the edges of the mesh to find the extreme vertex.
    • This is faster for large meshes but slower for small meshes.
    • Empirical data suggests around 32 vertices to be a good cut off.
    • This uses vertex count to determine which algorithm to use.
  • It also introduces initial validation of the mesh -- that validation absolutely necessary for the edge walking to provide a correct answer.
  • Several aspects of the implementation have been tested and tweaked for performance. See:
    • use of vector<int8_t> in Convex::findExtremeVertex
    • cache-friendly implementation of adjacency graph Convex::neighbors_.

This change is Reviewable

Copy link
Contributor Author

@SeanCurtis-TRI SeanCurtis-TRI left a 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.

Reviewable status: 0 of 6 files reviewed, all discussions resolved (waiting on @DamrongGuoy)

@SeanCurtis-TRI SeanCurtis-TRI force-pushed the PR_final_smarter_convex branch 3 times, most recently from 0367bc6 to 7b4285b Compare August 6, 2020 20:44
Copy link
Contributor

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

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

Checkpoint. I only finished the first two files (convex.h and convex-inl.h). One algorithmic detail needs attention in convex-inl.hfindExtremeVertex().

I'll continue next week.

Reviewed 2 of 6 files at r1.
Reviewable status: 2 of 6 files reviewed, 21 unresolved discussions (waiting on @DamrongGuoy and @SeanCurtis-TRI)


include/fcl/geometry/shape/convex.h, line 99 at r1 (raw file):

  /// @warning: The %Convex class only partially validates the input; it
  /// generally trusts that the inputs truly represent a coherent convex
  /// polytope. For those aspects that *are* validated, the constructor will

Optional. Should we write down the aspects that are validated as promised by this contract?


include/fcl/geometry/shape/convex.h, line 174 at r1 (raw file):

  /// frame C as the vertices of `this` %Convex polytope.
  /// @retval p_CE the position vector from Frame C's origin to the extreme
  ///         vertex E. It is guaranteed that v⋅E ≥ v⋅F for all F ≠ E in the

Optional. Is it intentional to use the frame-free expression v⋅E ≥ v⋅F for conciseness? Or it's supposed to be v_C⋅p_CE ≥ v_C⋅p_CF ?


include/fcl/geometry/shape/convex.h, line 199 at r1 (raw file):

  //
  // Invoking this *can* have side effects. Internal configuration can change
  // based failed validation tests.

Nit: "based on failed validation tests." ?


include/fcl/geometry/shape/convex.h, line 253 at r1 (raw file):

  // If true, findExtremeVertex() can reliably use neighbor_vertices_ to walk
  // along the surface of the mesh. If false, it must linearly search.
  bool extent_from_edges_{false};

Block. The name "extent_from_edges" is obscure to me. Does "extent" here mean "finding extreme vertex"? Does "from edges" mean "using neighbors"?

How about "find_extreme_via_neighbors", and we don't need to explain through comments?

From GSG:
"But remember: while comments are very important, the best code is self-documenting. Giving sensible names to types and variables is much better than using obscure names that you must then explain through comments."
https://drake.mit.edu/styleguide/cppguide.html#Comments


include/fcl/geometry/shape/convex.h, line 233 at r2 (raw file):

   The figure below shows that for vertex j, entry j tells us to jump into
   the vector at neighbors_[j]. At that location, is the number of vertices

Optional. "the vector at the neighbors_[j]-th entry".


include/fcl/geometry/shape/convex.h, line 234 at r2 (raw file):

   The figure below shows that for vertex j, entry j tells us to jump into
   the vector at neighbors_[j]. At that location, is the number of vertices
   adjacent to j (mⱼ). The next mⱼ entries starting at neighbors_[j] + 1 are

Optional. j (mⱼ) looks like function j of mⱼ. How about this?

the number of vertices adjacent to vertex j, denoted by mⱼ.

include/fcl/geometry/shape/convex.h, line 234 at r2 (raw file):

   The figure below shows that for vertex j, entry j tells us to jump into
   the vector at neighbors_[j]. At that location, is the number of vertices
   adjacent to j (mⱼ). The next mⱼ entries starting at neighbors_[j] + 1 are

Optional. "starting at neighbors_[j]+1-th entry"


include/fcl/geometry/shape/convex.h, line 244 at r2 (raw file):

            0 ...   j             ↑   ↑ ... ↑
                                 Indices of vertex j's
                                 neighboring vertices.

The picture is very useful. Thanks.


include/fcl/geometry/shape/convex-inl.h, line 285 at r2 (raw file):

        visited[neighbor_index] = 1;
        S neighbor_value = v_C.dot(vertices[neighbor_index]);
        if (neighbor_value > extreme_value) {

Block. Please fix the following algorithmic problem by:

  1. Add a unit test of a tricky case below.
  2. Change ">" to ">=" and verify that it fixes the problem.

If all neighbors of extreme_index has the same value as extreme_index, we still need to continue the search. An example is the pyramid with v0 = (0,0,0) at the center of its square base, as shown below, with v_C = (0,0,1) = +Z direction.

Starting with extreme_index = 0, we have extreme_value = 0, which is equal to neighbor_value of all neighbors. With "if ( > )", the search stops at v0, but the correct answer is v5 with value = +1.

Vector3d points_C[] = {
  Vector3d::Zero(), // v0
  Vector3d::UnitX(), // v1
  Vector3d::UnitY(), // v2
  -Vector3d::UnitX(), // v3
  -Vector3d::UnitY(), // v4
  Vector3d::UnitZ() // v5
};
// Four triangles that make the square base of the pyramid.
add_faces({0,1,4}, {0,4,3}, {0,3,2}, {0,2,1});
// Four triangular faces of the pyramid.
add_faces({4,1,5}, {1,2,5}, {2,3,5}, {3,4,5});
  //
  //         +Z
  //          |
  //          v5
  //          |  v3
  //          | /
  //          |/
  //  v4------v0-----v2---+Y
  //         /
  //        /
  //      v1
  //      /
  //    +X
  //

include/fcl/geometry/shape/convex-inl.h, line 331 at r2 (raw file):

  bool all_connected = true;
  // Build a map from each edge to the number of faces adjacent to it. First,
  // pre-populate all the edges found in in the vertex neighbor calculation.

Nit: s/"in in"/"in".


include/fcl/geometry/shape/convex-inl.h, line 332 at r2 (raw file):

  // Build a map from each edge to the number of faces adjacent to it. First,
  // pre-populate all the edges found in in the vertex neighbor calculation.
  std::map<std::pair<int, int>, int> edge_faces;

Optional. Rename to num_face_of_edge or edge_to_num_face and trim down the comment like this:

std::map<std::pair<int, int>, int> num_face_of_edge;
// First, pre-populate all the edges found in in the vertex neighbor
// calculation.
for (int v = 0; v < static_cast<int>(vertices_->size()); ++v) {

When I first saw edge_faces, I thought it's the collection of faces adjacent to an edge.

"Giving sensible names to types and variables is much better than using obscure names that you must then explain through comments."
https://drake.mit.edu/styleguide/cppguide.html#Comments


include/fcl/geometry/shape/convex-inl.h, line 338 at r2 (raw file):

    if (neighbor_count == 0) {
      if (all_connected) {
        ss << "\n Not all vertices are connected";

Nit: Want a period "." at the end of sentence?


include/fcl/geometry/shape/convex-inl.h, line 341 at r2 (raw file):

        all_connected = false;
      }
      ss << "\n  Vertex " << v << " is not included in any faces";

Nit: Want a period "." at the end of sentence?


include/fcl/geometry/shape/convex-inl.h, line 353 at r2 (raw file):

  // directly from the neighbor list because a degenerate mesh where more than
  // two faces shared an edge would still result in the edge's vertices listing
  // each other as edges and nothing more. We must explicitly handle the faces.

Optional. Split one long sentence into two sentences, perhaps like this.

  // Explicitly visit the faces and examine edges. Note: this can't be done
  // directly from the neighbor list for degenerate meshes where more than
  // two faces shared an edge. Such an edge would still result in its two vertices
  // listing each other as edges and nothing more. We must explicitly handle
  // the faces.

include/fcl/geometry/shape/convex-inl.h, line 355 at r2 (raw file):

  // each other as edges and nothing more. We must explicitly handle the faces.
  const std::vector<int>& faces = *faces_;
  int face_index = 0;

Optional. face_index sounds like 0th face, 1st face, 2nd face, etc. How about face_begin, face_start, or face_start_index ?


include/fcl/geometry/shape/convex-inl.h, line 369 at r2 (raw file):

  // Now examine the results.
  bool is_watertight = true;
  for (const auto& key_value_pair : edge_faces) {

Optional. I wonder whether structured bindings would work here?

for (const auto& [edge, count] : edge_faces) {

include/fcl/geometry/shape/convex-inl.h, line 375 at r2 (raw file):

      if (is_watertight) {
        is_watertight = false;
        ss << "\n The mesh is not watertight";

Nit: Want a period "." at the end of sentence?


include/fcl/geometry/shape/convex-inl.h, line 378 at r2 (raw file):

      }
      ss << "\n  Edge between vertices " << edge.first << " and " << edge.second
         << " is shared by " << count << " faces (should be 2)";

Nit: Want a period "." at the end of sentence?


include/fcl/geometry/shape/convex-inl.h, line 396 at r2 (raw file):

  // we rely on the set to eliminate the redundant declaration and then dump
  // the results to a more compact representation: the vector.
  std::vector<std::set<int>> neighbors(vertices_->size());

Optional. Explain that the deterministic ordering in set is important, perhaps for repeatability of downstream applications? Otherwise, we could have used unordered_set?


include/fcl/geometry/shape/convex-inl.h, line 412 at r2 (raw file):

  }
  // Instantiate a bunch of empty vectors for each vertex.
  std::vector<std::vector<int>> neighbor_vertices;

Optional. Explain the purpose of vector<vector<int>> neighbor_vertices. I think we can go directly from vector<set<int>> neighbors to the class data member vector<int> neighbors_. Why we need neighbor_vertices in between? Is it for a performance reason?


include/fcl/geometry/shape/convex-inl.h, line 413 at r2 (raw file):

  // Instantiate a bunch of empty vectors for each vertex.
  std::vector<std::vector<int>> neighbor_vertices;
  neighbor_vertices = std::vector<std::vector<int>>(vertices.size());

Optional. Could the two lines above become this one line please?

std::vector<std::vector<int>> neighbor_vertices(vertices.size());

Or the compiler didn't like it?

Copy link

@jmirabel jmirabel left a comment

Choose a reason for hiding this comment

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

Reviewable status: 2 of 6 files reviewed, 22 unresolved discussions (waiting on @DamrongGuoy and @SeanCurtis-TRI)


include/fcl/geometry/shape/convex-inl.h, line 285 at r2 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Block. Please fix the following algorithmic problem by:

  1. Add a unit test of a tricky case below.
  2. Change ">" to ">=" and verify that it fixes the problem.

If all neighbors of extreme_index has the same value as extreme_index, we still need to continue the search. An example is the pyramid with v0 = (0,0,0) at the center of its square base, as shown below, with v_C = (0,0,1) = +Z direction.

Starting with extreme_index = 0, we have extreme_value = 0, which is equal to neighbor_value of all neighbors. With "if ( > )", the search stops at v0, but the correct answer is v5 with value = +1.

Vector3d points_C[] = {
  Vector3d::Zero(), // v0
  Vector3d::UnitX(), // v1
  Vector3d::UnitY(), // v2
  -Vector3d::UnitX(), // v3
  -Vector3d::UnitY(), // v4
  Vector3d::UnitZ() // v5
};
// Four triangles that make the square base of the pyramid.
add_faces({0,1,4}, {0,4,3}, {0,3,2}, {0,2,1});
// Four triangular faces of the pyramid.
add_faces({4,1,5}, {1,2,5}, {2,3,5}, {3,4,5});
  //
  //         +Z
  //          |
  //          v5
  //          |  v3
  //          | /
  //          |/
  //  v4------v0-----v2---+Y
  //         /
  //        /
  //      v1
  //      /
  //    +X
  //

That's neat. If not wrong, this degenerate case can happen only at the very first iteration. If it happens at the first, it can happen at the next if the convex has parallel consecutive faces. As soon as you have one strict improvement, you can safely use > for the rest of the algo.


include/fcl/geometry/shape/convex-inl.h, line 270 at r3 (raw file):

  // definitive.
  std::vector<int8_t> visited(vertices.size(), 0);
  int extreme_index = 0;

You can expect substantial improvement by caching this value. This can be achieved by make supportConvex a temporary class method, and store the last index as a class attribute.

@jmirabel
Copy link

jmirabel commented Aug 7, 2020


include/fcl/geometry/shape/convex-inl.h, line 268 at r3 (raw file):

  // Note: A small amount of empirical testing suggests that a vector of int8_t
  // yields a slight performance improvement over int and bool. This is *not*
  // definitive.

I suspect this is an arbitrage. std::vector<bool> is more cache-friendly than int8_t but there is an extra calculation which bit into which byte (i.e. int8_t) must be read. This depends on the number of vertices and on your hardware. Did you try with a large number of vertices (where large depends on your cache size) ?

Copy link
Contributor Author

@SeanCurtis-TRI SeanCurtis-TRI left a comment

Choose a reason for hiding this comment

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

Comments addressed.

Reviewable status: 0 of 6 files reviewed, 7 unresolved discussions (waiting on @DamrongGuoy and @jmirabel)


include/fcl/geometry/shape/convex.h, line 99 at r1 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. Should we write down the aspects that are validated as promised by this contract?

I considered that, but wanted to be fill in validation without changing the contract. In my mind, this comment will only change when its no longer partially validated.


include/fcl/geometry/shape/convex.h, line 174 at r1 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. Is it intentional to use the frame-free expression v⋅E ≥ v⋅F for conciseness? Or it's supposed to be v_C⋅p_CE ≥ v_C⋅p_CF ?

Exactly right. Conciseness. However, it caught your attention and as I revisit it, I'm not persuaded that it provides value. So, I'm spelling it out.


include/fcl/geometry/shape/convex.h, line 199 at r1 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Nit: "based on failed validation tests." ?

Done


include/fcl/geometry/shape/convex.h, line 253 at r1 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Block. The name "extent_from_edges" is obscure to me. Does "extent" here mean "finding extreme vertex"? Does "from edges" mean "using neighbors"?

How about "find_extreme_via_neighbors", and we don't need to explain through comments?

From GSG:
"But remember: while comments are very important, the best code is self-documenting. Giving sensible names to types and variables is much better than using obscure names that you must then explain through comments."
https://drake.mit.edu/styleguide/cppguide.html#Comments

Done


include/fcl/geometry/shape/convex.h, line 233 at r2 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. "the vector at the neighbors_[j]-th entry".

OK Leaving it as is.


include/fcl/geometry/shape/convex.h, line 234 at r2 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. j (mⱼ) looks like function j of mⱼ. How about this?

the number of vertices adjacent to vertex j, denoted by mⱼ.

Good point. I juggled the sentence around.


include/fcl/geometry/shape/convex.h, line 234 at r2 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. "starting at neighbors_[j]+1-th entry"

OK As before, I'm leaving this as is.


include/fcl/geometry/shape/convex-inl.h, line 285 at r2 (raw file):

Previously, jmirabel (Joseph Mirabel) wrote…

That's neat. If not wrong, this degenerate case can happen only at the very first iteration. If it happens at the first, it can happen at the next if the convex has parallel consecutive faces. As soon as you have one strict improvement, you can safely use > for the rest of the algo.

Well spotted. I agree with your assessment. And thanks for the convex definition. :)

In the long run, we'll be able to alleviate that by either defining that as an "invalid" mesh or merging those faces at the time of construction. But for now, you are correct on the need for the modification.

Fortunately, I'd added the visited member; without that visited history, >= could potentially lead to an infinite loop. :)

The good news is that this shouldn't impact performance for 99.99999% of queries. So, it's cheap insurance to have.


include/fcl/geometry/shape/convex-inl.h, line 331 at r2 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Nit: s/"in in"/"in".

Done


include/fcl/geometry/shape/convex-inl.h, line 332 at r2 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. Rename to num_face_of_edge or edge_to_num_face and trim down the comment like this:

std::map<std::pair<int, int>, int> num_face_of_edge;
// First, pre-populate all the edges found in in the vertex neighbor
// calculation.
for (int v = 0; v < static_cast<int>(vertices_->size()); ++v) {

When I first saw edge_faces, I thought it's the collection of faces adjacent to an edge.

"Giving sensible names to types and variables is much better than using obscure names that you must then explain through comments."
https://drake.mit.edu/styleguide/cppguide.html#Comments

Done


include/fcl/geometry/shape/convex-inl.h, line 338 at r2 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Nit: Want a period "." at the end of sentence?

Done


include/fcl/geometry/shape/convex-inl.h, line 341 at r2 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Nit: Want a period "." at the end of sentence?

Done


include/fcl/geometry/shape/convex-inl.h, line 353 at r2 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. Split one long sentence into two sentences, perhaps like this.

  // Explicitly visit the faces and examine edges. Note: this can't be done
  // directly from the neighbor list for degenerate meshes where more than
  // two faces shared an edge. Such an edge would still result in its two vertices
  // listing each other as edges and nothing more. We must explicitly handle
  // the faces.

Done I went for a full rephrasing.


include/fcl/geometry/shape/convex-inl.h, line 355 at r2 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. face_index sounds like 0th face, 1st face, 2nd face, etc. How about face_begin, face_start, or face_start_index ?

Ok This is the pattern that appears over and over in this file. I'm going to leave this matching for consistency.


include/fcl/geometry/shape/convex-inl.h, line 369 at r2 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. I wonder whether structured bindings would work here?

for (const auto& [edge, count] : edge_faces) {

OK Not currently supported in CI.


include/fcl/geometry/shape/convex-inl.h, line 375 at r2 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Nit: Want a period "." at the end of sentence?

Done


include/fcl/geometry/shape/convex-inl.h, line 378 at r2 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Nit: Want a period "." at the end of sentence?

Done


include/fcl/geometry/shape/convex-inl.h, line 396 at r2 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. Explain that the deterministic ordering in set is important, perhaps for repeatability of downstream applications? Otherwise, we could have used unordered_set?

Ok Neither of those is strictly true. We don't require the ordering of set, nor is it inherently obvious that unordered_set would provide a measurable performance improvement (particularly as this is a one-time operation upon construction). The sole purpose of using a set has been documented.


include/fcl/geometry/shape/convex-inl.h, line 412 at r2 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. Explain the purpose of vector<vector<int>> neighbor_vertices. I think we can go directly from vector<set<int>> neighbors to the class data member vector<int> neighbors_. Why we need neighbor_vertices in between? Is it for a performance reason?

Done

That was leftover from when I was changing from one adjacency graph representation to the other. The intermediate step isn't actually required.


include/fcl/geometry/shape/convex-inl.h, line 413 at r2 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. Could the two lines above become this one line please?

std::vector<std::vector<int>> neighbor_vertices(vertices.size());

Or the compiler didn't like it?

OK No longer relevant.


include/fcl/geometry/shape/convex-inl.h, line 268 at r3 (raw file):

Previously, jmirabel (Joseph Mirabel) wrote…

I suspect this is an arbitrage. std::vector<bool> is more cache-friendly than int8_t but there is an extra calculation which bit into which byte (i.e. int8_t) must be read. This depends on the number of vertices and on your hardware. Did you try with a large number of vertices (where large depends on your cache size) ?

Agreed. I ran this with convex meshes with roughly 15-17 thousand vertices. It was a measurable performance improvement.


include/fcl/geometry/shape/convex-inl.h, line 270 at r3 (raw file):

Previously, jmirabel (Joseph Mirabel) wrote…

You can expect substantial improvement by caching this value. This can be achieved by make supportConvex a temporary class method, and store the last index as a class attribute.

Agreed; you'll note that there's a TODO at the top of this function in which we rely on coherency to remember this exact value. I'm disinclined to stash it inside the method as that will render this class incompatible with multi-threaded operations. It's one of the reasons that "visited" vector is re-allocated with each call. There's a bit of savings with allocate once and merely clearing it, but it's no longer threadsafe.

The better solution is to modify the GJK algorithm to store cache data per execution and make sure it gets passed in.

Copy link
Contributor

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

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

Checkpoint. I am reviewing test_convex.cpp.

Reviewed 1 of 6 files at r1, 2 of 4 files at r4.
Reviewable status: 3 of 6 files reviewed, 8 unresolved discussions (waiting on @DamrongGuoy, @jmirabel, and @SeanCurtis-TRI)


include/fcl/geometry/shape/convex-inl.h, line 285 at r2 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

Well spotted. I agree with your assessment. And thanks for the convex definition. :)

In the long run, we'll be able to alleviate that by either defining that as an "invalid" mesh or merging those faces at the time of construction. But for now, you are correct on the need for the modification.

Fortunately, I'd added the visited member; without that visited history, >= could potentially lead to an infinite loop. :)

The good news is that this shouldn't impact performance for 99.99999% of queries. So, it's cheap insurance to have.

Thank you. I unblock now. Set status to Satisfied ✔️.


include/fcl/geometry/shape/convex-inl.h, line 332 at r2 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

Done

Thank you. I like per_edge_face_count.


include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h, line 2516 at r4 (raw file):

  const Vector3<S>& p_CE = c->convex->findExtremeVertex(dir_C);

  // No measure and express E in the original query frame Q: p_CE -> p_QE.

Nit: s/No/Now.


test/geometry/shape/test_convex.cpp, line 409 at r4 (raw file):

    EXPECT_TRUE(CompareMatrices(convex_W.findExtremeVertex(v_W), p_WE))
        << shape_W.description() << " at\n"
        << X_WS.matrix() << "\nusing scalar: " << ScalarString<S>::value();

Optional. In case of test failure, should we print v_W in the error message too? It's in a for loop, so it might help us find which iteration fails.


test/geometry/shape/test_convex.cpp, line 570 at r4 (raw file):

// should uniquely produce that vertex as the support vertex.
template <typename S>
void BuildTests(const Polytope<S>& polytope,

Optional. The name BuildTests sounds too generic. Change to a more specific name please. Perhaps BuildSupportVertexTests()?


test/geometry/shape/test_convex.cpp, line 570 at r4 (raw file):

// should uniquely produce that vertex as the support vertex.
template <typename S>
void BuildTests(const Polytope<S>& polytope,

Optional. Change the output parameter to the return value please.

template <typename S>
std::vector<SupportVertexTest<S>> BuildTests(const Polytope<S>& polytope) {

"Prefer using return values rather than output parameters".
https://drake.mit.edu/styleguide/cppguide.html#Output_Parameters


test/geometry/shape/test_convex.cpp, line 603 at r4 (raw file):

                           {0, 1. / sqrt(3.), 0},
                           {0, 0, sqrt(3. / 8)}};
    const Vector3d center = (points_T[0] + points_T[1] + points_T[2]) / 3.0;

Optional. Isn't it the same as const Vector3d center(0, 0, 0) ? Or you wanted to emphasize "averaging" ? Should we change to center(0, 0, 0) ?


test/geometry/shape/test_convex.cpp, line 624 at r4 (raw file):

};

// Test for special condition in findExtremeVertex which can arise iff the

Block. iff sounds too strong. Please soften it to something like:

// Test for special condition in findExtremeVertex which can arise in a
// Convex shape with co-planar faces.

"⇒" is not right because in addition to co-planar faces, we can also have co-linear edges that require the special condition. For example, we can insert a vertex in the middle of an edge of the tetrahedron instead of the middle of a triangle face. Then, two of the four triangles become two degenerated quadrilateral faces (quad that looks like triangle). Taking the edge midpoint as vertex 0 and the search direction perpendicular to the edge towards a non-neighbor vertex will require neighbor_value >= extreme_value in the search.

"⇐" is not right because cutting the square base of a pyramid into two co-planar faces does not require equality check, so neighbor_value > extreme_value without = would work.

I will not require testing examples with co-linear edges.

Copy link
Contributor

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

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

Checkpoint. There's only one more file to review.

Reviewed 1 of 6 files at r1, 1 of 4 files at r4.
Reviewable status: 5 of 6 files reviewed, 15 unresolved discussions (waiting on @DamrongGuoy, @jmirabel, and @SeanCurtis-TRI)

a discussion (no related file):
Blocking. Please correct the typo in the file name "test_gjk_libbcd-inl_gjk_initializer.cpp" (change "bcd" to "ccd").



test/geometry/shape/test_convex.cpp, line 129 at r4 (raw file):

    // The Polytope class makes the pointers to vertices and faces const access.
    // The Convex class calls for non-const pointers. Temporarily const-casting
    // them to make it compatible.

Blocking. I think this comment is stale. I see no const-casting here.


test/geometry/shape/test_convex.cpp, line 736 at r4 (raw file):

// of invalid topologies. We don't *explicitly* test the *valid* case because it
// is implicitly tested every time a Convex is created in these tests. We also
// don't care about the scalar types because this test is purely about topology.

Optional. Please add to the comment that this GTEST_TEST() tests the private functions ValidateMesh(), ValidateTopology(), and FindVertexNeighbors(). It took me a while to realize that the three functions were tested in this GTEST_TEST.


test/geometry/shape/test_convex.cpp, line 787 at r4 (raw file):

// A tessellated unit sphere; 8 longitudinal wedges and 8 latitudinal bands.
class Sphere final : public Polytope<double> {

Blocking. Please change the class name Sphere to be more specific like TessellatedUnitSphere. Otherwise, it is confused with the template Sphere<> in fcl/include/fcl/geometry/shape/sphere.h.


test/geometry/shape/test_convex.cpp, line 854 at r4 (raw file):

// Confirm that edge walking gets disabled in expected cases.
GTEST_TEST(ConvexGeometry, UseEdgeWalkingConditions) {
    const bool throw_if_invalid{true};

Optional. Would constexpr work here?


test/geometry/shape/test_convex.cpp, line 872 at r4 (raw file):

        Sphere poly;
        Convex<double> convex = poly.MakeConvex(throw_if_invalid);
        EXPECT_TRUE(ConvexTester::find_extreme_via_neighbors(convex));

Optional. I have seen findExtremeVertex() tested only on Convex of very small number of vertices. This tessellated sphere has many more vertices, but it's used for testing the flag find_extreme_via_neighbors_ only. How about using this tessellated sphere to test the function findExtremeVertex() too?

The motivation of this PR is to improve performance for Convex with a large number of vertices. Ideally I would like to see a test that compares running time of findExtremeVertex() when find_extreme_via_neighbors_ is set to true and to false on a Convex with many vertices. However, I understand it's not easy to set up such a test.


test/narrowphase/detail/convexity_based_algorithm/CMakeLists.txt, line 5 at r4 (raw file):

    test_gjk_libccd-inl_extractClosestPoints.cpp
    test_gjk_libccd-inl_gjk_doSimplex2.cpp
    test_gjk_libbcd-inl_gjk_initializer.cpp

Blocking. Please rename the file "test_gjk_libbcd-inl_gjk_initializer.cpp" to "test_gjk_libccd-inl_gjk_initializer.cpp".

Copy link
Contributor

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

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

Reviewable status: 5 of 6 files reviewed, 16 unresolved discussions (waiting on @DamrongGuoy, @jmirabel, and @SeanCurtis-TRI)

a discussion (no related file):
By the way, why Reviewable shows Finish! Squash & Retain branch ? I have not finished the review. Was it because I put the checkmark in one of my comments?


Copy link
Contributor Author

@SeanCurtis-TRI SeanCurtis-TRI left a comment

Choose a reason for hiding this comment

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

More comments addressed.

Reviewable status: 2 of 6 files reviewed, 8 unresolved discussions (waiting on @DamrongGuoy and @jmirabel)

a discussion (no related file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Blocking. Please correct the typo in the file name "test_gjk_libbcd-inl_gjk_initializer.cpp" (change "bcd" to "ccd").

BTW you don't have to type blocking. Anything that doesn't start with nit/minor/fyi/btw is automatically blocking.


a discussion (no related file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

By the way, why Reviewable shows Finish! Squash & Retain branch ? I have not finished the review. Was it because I put the checkmark in one of my comments?

No. I don't think Reviewable is well configured for FCL. Not like Drake. We can/should look into that probably. Moral of the story, for FCL you simply don't get trust Reviewable's judgment.



test/geometry/shape/test_convex.cpp, line 129 at r4 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Blocking. I think this comment is stale. I see no const-casting here.

Done.


test/geometry/shape/test_convex.cpp, line 409 at r4 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. In case of test failure, should we print v_W in the error message too? It's in a for loop, so it might help us find which iteration fails.

Done


test/geometry/shape/test_convex.cpp, line 570 at r4 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. The name BuildTests sounds too generic. Change to a more specific name please. Perhaps BuildSupportVertexTests()?

Done


test/geometry/shape/test_convex.cpp, line 570 at r4 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. Change the output parameter to the return value please.

template <typename S>
std::vector<SupportVertexTest<S>> BuildTests(const Polytope<S>& polytope) {

"Prefer using return values rather than output parameters".
https://drake.mit.edu/styleguide/cppguide.html#Output_Parameters

Done


test/geometry/shape/test_convex.cpp, line 603 at r4 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. Isn't it the same as const Vector3d center(0, 0, 0) ? Or you wanted to emphasize "averaging" ? Should we change to center(0, 0, 0) ?

sure; but the formulation guarantees it's the centroid no matter what happens to the constant values in the previous declaration. Someone doesn't have to do math to understand the code; they can just see it's the definition of a centroid.


test/geometry/shape/test_convex.cpp, line 624 at r4 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Block. iff sounds too strong. Please soften it to something like:

// Test for special condition in findExtremeVertex which can arise in a
// Convex shape with co-planar faces.

"⇒" is not right because in addition to co-planar faces, we can also have co-linear edges that require the special condition. For example, we can insert a vertex in the middle of an edge of the tetrahedron instead of the middle of a triangle face. Then, two of the four triangles become two degenerated quadrilateral faces (quad that looks like triangle). Taking the edge midpoint as vertex 0 and the search direction perpendicular to the edge towards a non-neighbor vertex will require neighbor_value >= extreme_value in the search.

"⇐" is not right because cutting the square base of a pyramid into two co-planar faces does not require equality check, so neighbor_value > extreme_value without = would work.

I will not require testing examples with co-linear edges.

I've corrected the language.


test/geometry/shape/test_convex.cpp, line 736 at r4 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. Please add to the comment that this GTEST_TEST() tests the private functions ValidateMesh(), ValidateTopology(), and FindVertexNeighbors(). It took me a while to realize that the three functions were tested in this GTEST_TEST.

If I understand correctly, your concern was that you were looking for tests that explicitly tested those private methods, correct?

I'm going to leave this test doc as is, because it doesn't claim to test methods, but tests conditions to the constructor. All it does is call the constructor with known bad conditions.


test/geometry/shape/test_convex.cpp, line 787 at r4 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Blocking. Please change the class name Sphere to be more specific like TessellatedUnitSphere. Otherwise, it is confused with the template Sphere<> in fcl/include/fcl/geometry/shape/sphere.h.

Done


test/geometry/shape/test_convex.cpp, line 854 at r4 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. Would constexpr work here?

It would work but wouldn't have any semantic difference to the code. Where it would matter most is if I were using this const value in a function that could be constexpr if its parameters were constexpr. But that doesn't happen here. In this context, the two are equivalent.


test/geometry/shape/test_convex.cpp, line 872 at r4 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Optional. I have seen findExtremeVertex() tested only on Convex of very small number of vertices. This tessellated sphere has many more vertices, but it's used for testing the flag find_extreme_via_neighbors_ only. How about using this tessellated sphere to test the function findExtremeVertex() too?

The motivation of this PR is to improve performance for Convex with a large number of vertices. Ideally I would like to see a test that compares running time of findExtremeVertex() when find_extreme_via_neighbors_ is set to true and to false on a Convex with many vertices. However, I understand it's not easy to set up such a test.

</blockquote></details>

Unit tests don't validate performance. This is about correctness. If you feel the coverage of the tests are insufficient to indicate correctness, then we can address that. But unit tests are never run in a context where you should rely on performance being meaningful.
___
*[test/narrowphase/detail/convexity_based_algorithm/CMakeLists.txt, line 5 at r4](https://reviewable.io/reviews/flexible-collision-library/fcl/488#-MEfW6S-DN8T6PYiaeya:-MEhUT6H7s6Rjqbtaqdz:b-6g4fu2) ([raw file](https://github.com/flexible-collision-library/fcl/blob/7245c171091f456c6d3c350ae1153edd37c0230b/test/narrowphase/detail/convexity_based_algorithm/CMakeLists.txt#L5)):*
<details><summary><i>Previously, DamrongGuoy (Damrong Guoy) wrote…</i></summary><blockquote>

Blocking. Please rename the file "test_gjk_lib**bcd**-inl_gjk_initializer.cpp" to "test_gjk_lib**ccd**-inl_gjk_initializer.cpp".
</blockquote></details>

BTW You don't have to post this comment twice.  :)


<!-- Sent from Reviewable.io -->

Copy link
Contributor

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

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

:lgtm:

Reviewed 4 of 4 files at r5.
Reviewable status: all files reviewed, 3 unresolved discussions (waiting on @jmirabel and @SeanCurtis-TRI)

a discussion (no related file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

BTW you don't have to type blocking. Anything that doesn't start with nit/minor/fyi/btw is automatically blocking.

Thank you. Yes, I know. I put it to remind myself. I don't get good visual signals from Reviewable's icons. (And the confusing btw, which is not Blocking(-) or Discussing(o) but Informing(i).)

Set to Satisfied now.



include/fcl/geometry/shape/convex-inl.h, line 268 at r3 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

Agreed. I ran this with convex meshes with roughly 15-17 thousand vertices. It was a measurable performance improvement.

@jmirabel Could you please unblock this comment? Click on ✔️ please.
image.png


include/fcl/geometry/shape/convex-inl.h, line 270 at r3 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

Agreed; you'll note that there's a TODO at the top of this function in which we rely on coherency to remember this exact value. I'm disinclined to stash it inside the method as that will render this class incompatible with multi-threaded operations. It's one of the reasons that "visited" vector is re-allocated with each call. There's a bit of savings with allocate once and merely clearing it, but it's no longer threadsafe.

The better solution is to modify the GJK algorithm to store cache data per execution and make sure it gets passed in.

@jmirabel Could you please unblock this comment?


test/geometry/shape/test_convex.cpp, line 129 at r4 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

Done.

Satisfied.


test/geometry/shape/test_convex.cpp, line 624 at r4 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

I've corrected the language.

This is why face-to-face discussion would have been easier. Sorry that my previous description didn't go well. I set to Satisfied now since it's a minor communication problem.

To me, the word "iff" has a specific mathematical meaning. If we have changed the math "iff" to english "when", it would have fixed my allergy.

Mathematically when we use "iff" we need to prove that it is true in both directions. The good thing is that this revision r5 is an improvement over the previous one. Now "⇐" is correct, thank you!

However, "⇒" is still incorrect; previously I tried to describe this counter example: co-linear edges without co-planar faces. It looks like this:

  //
  //         +Z
  //          |
  //  v4------|------v3 
  //          |  v2
  //          | /
  //          |/
  //          v0----------+Y
  //         /
  //        /
  //       v1
  //      /
  //    +X
  //
vertices = {v0=(0,0,0), v1=(1,0,0), v2=(-1,0,0), v3=(0,1,1), v4=(0,-1,1)}

// Each of 1st and 2nd faces is a quadrilateral with two co-linear edges.
// Each of 3rd and 4th faces is a triangle.
faces = {{v0,v2,v3,v1}, {v0,v1,v4,v2}, {v1,v3,v4}, {v2,v4,v3}}

I started with the original tetrahedron v1v2v3v4 and divide the edge v1v2 into co-linear edges v0v1 and v0v2. Each of the two original triangles v1v2v3 and v1v4v2 becomes a quadrilateral sharing the two co-linear edges v0v1 and v0v2.

With starting vertex v0 and the query direction +Z, we would need the special treatment in the same way as the co-planar example in GTEST_TEST. This is despite the fact that there are no co-planar faces in this example.

In other words, after removing co-planar faces, we also need to remove the remaining co-linear edges in order to switch >= back to >.

Sorry for bothering with so many details. I set to Satisfied.


test/geometry/shape/test_convex.cpp, line 787 at r4 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

Done

Satisfied.


test/geometry/shape/test_convex.cpp, line 872 at r4 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

Unit tests don't validate performance. This is about correctness. If you feel the coverage of the tests are insufficient to indicate correctness, then we can address that. But unit tests are never run in a context where you should rely on performance being meaningful.

Satisfied. I agree that unit tests are not for validating performance.

I'm just curious where/how to validate performance? It's an open problem, I guess. How would our system automatically detect if someone unintentionally makes the code slow again?


test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_gjk_initializer.cpp, line 161 at r5 (raw file):

  ::testing::InitGoogleTest(&argc, argv);
  return RUN_ALL_TESTS();
}

Discussing. Just for my education. I see this main() as a common practice in fcl but not in drake. Any explanation?

Copy link
Contributor Author

@SeanCurtis-TRI SeanCurtis-TRI left a comment

Choose a reason for hiding this comment

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

+@sherm1 for platform review, please.

Reviewable status: all files reviewed, 2 unresolved discussions (waiting on @jmirabel and @sherm1)


include/fcl/geometry/shape/convex-inl.h, line 270 at r3 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

@jmirabel Could you please unblock this comment?

Done.


test/geometry/shape/test_convex.cpp, line 624 at r4 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

This is why face-to-face discussion would have been easier. Sorry that my previous description didn't go well. I set to Satisfied now since it's a minor communication problem.

To me, the word "iff" has a specific mathematical meaning. If we have changed the math "iff" to english "when", it would have fixed my allergy.

Mathematically when we use "iff" we need to prove that it is true in both directions. The good thing is that this revision r5 is an improvement over the previous one. Now "⇐" is correct, thank you!

However, "⇒" is still incorrect; previously I tried to describe this counter example: co-linear edges without co-planar faces. It looks like this:

  //
  //         +Z
  //          |
  //  v4------|------v3 
  //          |  v2
  //          | /
  //          |/
  //          v0----------+Y
  //         /
  //        /
  //       v1
  //      /
  //    +X
  //
vertices = {v0=(0,0,0), v1=(1,0,0), v2=(-1,0,0), v3=(0,1,1), v4=(0,-1,1)}

// Each of 1st and 2nd faces is a quadrilateral with two co-linear edges.
// Each of 3rd and 4th faces is a triangle.
faces = {{v0,v2,v3,v1}, {v0,v1,v4,v2}, {v1,v3,v4}, {v2,v4,v3}}

I started with the original tetrahedron v1v2v3v4 and divide the edge v1v2 into co-linear edges v0v1 and v0v2. Each of the two original triangles v1v2v3 and v1v4v2 becomes a quadrilateral sharing the two co-linear edges v0v1 and v0v2.

With starting vertex v0 and the query direction +Z, we would need the special treatment in the same way as the co-planar example in GTEST_TEST. This is despite the fact that there are no co-planar faces in this example.

In other words, after removing co-planar faces, we also need to remove the remaining co-linear edges in order to switch >= back to >.

Sorry for bothering with so many details. I set to Satisfied.

I think you misread the new text -- you were probably expecting to see something different from what I wrote.

My description exactly satisfies your co-linear edges. My definition is that v0 must be co-planar with all of its adjacent vertices. In your co-linear edge, v0 is co-planar with v1 and v2 -- admittedly, there is an infinite set of planes they lie on together, but they are co-planar. I'm quite confident that the iff is correct now and the case you described is a subset of my description.

BTW I was never using a special meaning of "iff". I've always shared your meaning. The previous error was not using the term "iff" it was in mischaracterizing the conditions.


test/geometry/shape/test_convex.cpp, line 872 at r4 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Satisfied. I agree that unit tests are not for validating performance.

I'm just curious where/how to validate performance? It's an open problem, I guess. How would our system automatically detect if someone unintentionally makes the code slow again?

I created a test harness in Drake where I parameterized the geometry in collision so I could characterize the performance w.r.t. mesh resolution. That, for example, is where the 32-vertex line was drawn from.


test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_gjk_initializer.cpp, line 161 at r5 (raw file):

Previously, DamrongGuoy (Damrong Guoy) wrote…

Discussing. Just for my education. I see this main() as a common practice in fcl but not in drake. Any explanation?

Drake has introduced harness where the gtest entry point is built into the build system. FCL doesn't have that, so each test has to explicitly include it.

Copy link
Contributor

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

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

Reviewable status: all files reviewed, 2 unresolved discussions (waiting on @jmirabel and @sherm1)

Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

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

Looks great so far! Checkpoint -- just the tests remaining to review.

Reviewed 2 of 4 files at r4, 2 of 4 files at r5.
Reviewable status: all files reviewed, 4 unresolved discussions (waiting on @SeanCurtis-TRI)


include/fcl/geometry/shape/convex.h, line 170 at r5 (raw file):

  std::vector<Vector3<S>> getBoundVertices(const Transform3<S>& tf) const;

  /// @brief Reports a vertex in this convex polytope that lies most in the

nit: consider "most" -> "furthest"


include/fcl/geometry/shape/convex.h, line 199 at r5 (raw file):

  //
  // Invoking this *can* have side effects. Internal configuration can change
  // based on failed validation tests.

BTW I don't know what you mean by "internal configuration" here. Can this be made more specific?


include/fcl/geometry/shape/convex.h, line 206 at r5 (raw file):

  // Reports if the mesh is watertight and that every vertex is part of a face.
  // The mesh is watertight if every edge is shared by two unique faces.

nit: not sure what "unique" means here -- consider "different" instead if that's the meaning?


include/fcl/geometry/shape/convex.h, line 248 at r5 (raw file):

   A modicum testing indicated that this compact representation led to
   measurably improved performance for findExtremeVertex() -- initial
   hypothesis attributes it to improved cache hits. */

BTW would be cleaner I think to split this into two std::vectors to avoid packing together two different data structures, something like:

std::vector<int> index_into_neighbors_; // access by vertex index
std::vector<int> neighbors_; // indexed by previous member

I would expect that to have equally good memory access patterns. Was that the original layout that this one outperforms?


include/fcl/geometry/shape/convex-inl.h, line 65 at r5 (raw file):

      num_faces_(num_faces),
      faces_(faces),
      find_extreme_via_neighbors_{vertices->size() > 32} {

nit: consider a named constant for the magic threshold here


include/fcl/geometry/shape/convex-inl.h, line 74 at r5 (raw file):

    sum += vertex;
  }
  interior_point_ = sum * (S)(1.0 / vertices_->size());

btw do we enforce somewhere that there is at least one vertex? Otherwise this could be 0/0 = NaN. If size > 0 is a precondition should enforce that somewhere.


include/fcl/geometry/shape/convex-inl.h, line 264 at r5 (raw file):

  // TODO(SeanCurtis-TRI): Create an override of this that seeds the search with
  //  the last extremal vertex index (assuming some kind of coherency in the
  //  evaluation sequence).

btw great idea! I bet that would help a lot.


include/fcl/geometry/shape/convex-inl.h, line 284 at r5 (raw file):

        if (visited[neighbor_index]) continue;
        visited[neighbor_index] = 1;
        S neighbor_value = v_C.dot(vertices[neighbor_index]);

btw can be const


include/fcl/geometry/shape/convex-inl.h, line 290 at r5 (raw file):

        //  following condition. Vertex 0 lies on a face whose plane is
        //  perpendicular to v_C. Furthermore, all of the faces that share
        //  vertex 0 lie on the same plane. In this case, searching for a strict

BTW a few thoughts:

  • Seems unlikely that we would ever know for sure that their weren't coplanar faces. Why not just plan on keeping the >= here forever and simply explain that it makes the code robust in case there are coplanar faces. That doesn't seem like a big cost and would avoid the TODO.
  • I was confused at first by the explanation here. Now I think you didn't really mean specifically "Vertex 0" but rather something like "Vertex i", that is, some arbitrary vertex. Is that right?
  • Also even dumber I forgot that v_C was the search direction by the time I got here and interpreted the "v" as "vertex". In case you want to take pity on the clueless, naming that "d" or "dir" for "direction" or something else non-v would avoid that confusion, however fleeting.

include/fcl/geometry/shape/convex-inl.h, line 366 at r5 (raw file):

  for (int f = 0; f < num_faces_; ++f) {
      const int vertex_count = faces[face_index];
      int prev_v = faces[face_index + vertex_count];

btw it took me a while to see that this is treating the last vertex as the "previous" one, especially with the slightly-odd indexing due to the count placement. (At first I though this was misnamed and should be "next_v".) A comment // Start with the last vertex of this face as the "previous" one. would have helped.


include/fcl/geometry/shape/convex-inl.h, line 377 at r5 (raw file):

  // Now examine the results.
  bool is_watertight = true;
  for (const auto& key_value_pair : per_edge_face_count) {

btw a structured binding would be nicer here: auto& [edge, count] = (are we allowed to use those in FCL?)


include/fcl/geometry/shape/convex-inl.h, line 424 at r5 (raw file):

  // Now build the encoded adjacency graph as documented.
  neighbors_.resize(v_count, -1);

btw I expected to see a check for leftover "-1"s below but I see you are just initializing this for sanity rather than bug catching. Worth mentioning that in a comment here just to be clear about the purpose of the "-1", since a non-initializing resize() would also work. Or is this necessary so valgrind won't get upset about copying uninitialized memory as the vector is expanded?


include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h, line 2520 at r5 (raw file):

  v->v[1] = p_CE(1);
  v->v[2] = p_CE(2);
  ccdQuatRotVec(v, &c->rot);

btw does this actually do both a rotation and translation?

Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

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

Platform :lgtm_strong: pending a few minor comments. The unit tests are awesome as usual!

Reviewed 2 of 4 files at r5.
Reviewable status: all files reviewed, 8 unresolved discussions (waiting on @SeanCurtis-TRI)


test/geometry/shape/test_convex.cpp, line 640 at r5 (raw file):

  // We can expect an exact answer down to the last bit.
  EXPECT_TRUE(CompareMatrices(convex_W.findExtremeVertex(v_W), p_WE_expected));

btw doesn't CompareMatrices() work to a default non-zero tolerance?


test/geometry/shape/test_convex.cpp, line 851 at r5 (raw file):

  int vertex_count() const final { return 58; }
};
// Confirm that edge walking gets disabled in expected cases.

nit insert blank line


test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_gjk_initializer.cpp, line 35 at r5 (raw file):

 */

/** @author Sean Curts (sean.curtis@tri.global) */

nit: Curts -> Curtis ("Uh, yeah the programmer misspelled his own name ... but don't worry about the code!")


test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_gjk_initializer.cpp, line 72 at r5 (raw file):

 support function uses Convex::findExtremeVertex() so we're doing some spot
 checking on the general correctness and not the numerical nitty gritty
 (assuming that has been taken care of in the Convex unit tests.  */

nit: closing ")" missing


test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_gjk_initializer.cpp, line 141 at r5 (raw file):

       good. However, because this is in a unit test, the memory leak induced
       by not invoking this delete will be immediately eliminated by the
       testing process existing.  */

nit existing -> exiting

Copy link
Contributor Author

@SeanCurtis-TRI SeanCurtis-TRI left a comment

Choose a reason for hiding this comment

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

Hopefully haven't broken any CI.... But, otherwise, comments addressed.

Reviewable status: 2 of 6 files reviewed, all discussions resolved (waiting on @DamrongGuoy and @sherm1)


include/fcl/geometry/shape/convex.h, line 170 at r5 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

nit: consider "most" -> "furthest"

Done


include/fcl/geometry/shape/convex.h, line 199 at r5 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW I don't know what you mean by "internal configuration" here. Can this be made more specific?

Done


include/fcl/geometry/shape/convex.h, line 206 at r5 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

nit: not sure what "unique" means here -- consider "different" instead if that's the meaning?

Done


include/fcl/geometry/shape/convex.h, line 248 at r5 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW would be cleaner I think to split this into two std::vectors to avoid packing together two different data structures, something like:

std::vector<int> index_into_neighbors_; // access by vertex index
std::vector<int> neighbors_; // indexed by previous member

I would expect that to have equally good memory access patterns. Was that the original layout that this one outperforms?

That was one of the layouts that this outperforms.


include/fcl/geometry/shape/convex-inl.h, line 65 at r5 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

nit: consider a named constant for the magic threshold here

Done


include/fcl/geometry/shape/convex-inl.h, line 74 at r5 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

btw do we enforce somewhere that there is at least one vertex? Otherwise this could be 0/0 = NaN. If size > 0 is a precondition should enforce that somewhere.

Surely the parentheses guarantees that it's 1 / 0 = inf? However, you're right, that isn't validated currently. I've added it as a note of things that aren't validated yet.


include/fcl/geometry/shape/convex-inl.h, line 284 at r5 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

btw can be const

Done


include/fcl/geometry/shape/convex-inl.h, line 290 at r5 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW a few thoughts:

  • Seems unlikely that we would ever know for sure that their weren't coplanar faces. Why not just plan on keeping the >= here forever and simply explain that it makes the code robust in case there are coplanar faces. That doesn't seem like a big cost and would avoid the TODO.
  • I was confused at first by the explanation here. Now I think you didn't really mean specifically "Vertex 0" but rather something like "Vertex i", that is, some arbitrary vertex. Is that right?
  • Also even dumber I forgot that v_C was the search direction by the time I got here and interpreted the "v" as "vertex". In case you want to take pity on the clueless, naming that "d" or "dir" for "direction" or something else non-v would avoid that confusion, however fleeting.
  • This TODO is a bit antiquated. It's not "co-planar faces", per se, that is the problem. More generally, it is if a vertex is co-planar with its adjacent vertices.
  • In this case, "co-planar" is simply there exists a vector v such that v.dot(n) evaluates to exactly the same value for all n = {v}U{N(v)} (with some fast and loose notation there). That is detectable. And highly unlikely except in the most contrived cases (as shown in the test).
  • That said, the likelihood of this ever happening in the wild is close to nil. So, I've changed to TODO to a note.

include/fcl/geometry/shape/convex-inl.h, line 366 at r5 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

btw it took me a while to see that this is treating the last vertex as the "previous" one, especially with the slightly-odd indexing due to the count placement. (At first I though this was misnamed and should be "next_v".) A comment // Start with the last vertex of this face as the "previous" one. would have helped.

This pattern appears over and over in this file. It's got problems, definitely. But rather than fix up the entire file in this PR, I decided to propagate the pattern.


include/fcl/geometry/shape/convex-inl.h, line 377 at r5 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

btw a structured binding would be nicer here: auto& [edge, count] = (are we allowed to use those in FCL?)

Sadly, not yet. :(


include/fcl/geometry/shape/convex-inl.h, line 424 at r5 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

btw I expected to see a check for leftover "-1"s below but I see you are just initializing this for sanity rather than bug catching. Worth mentioning that in a comment here just to be clear about the purpose of the "-1", since a non-initializing resize() would also work. Or is this necessary so valgrind won't get upset about copying uninitialized memory as the vector is expanded?

Nope; my oversight. I forgot about the "default constructed" resize.


include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h, line 2520 at r5 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

btw does this actually do both a rotation and translation?

No. Only a rotation is necessary. Extreme vertices are translation invariant.


test/geometry/shape/test_convex.cpp, line 640 at r5 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

btw doesn't CompareMatrices() work to a default non-zero tolerance?

Nope. Default is zero.


test/geometry/shape/test_convex.cpp, line 851 at r5 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

nit insert blank line

Done


test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_gjk_initializer.cpp, line 72 at r5 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

nit: closing ")" missing

Done


test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_gjk_initializer.cpp, line 141 at r5 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

nit existing -> exiting

Done

Copy link
Contributor Author

@SeanCurtis-TRI SeanCurtis-TRI left a comment

Choose a reason for hiding this comment

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

@jamiesnape AppVeyor is suddenly crying about being unable to acquire Eigen.

  1. I tried the URL for the .tar.gz for bitbucket and it came up "dead". Trying to go to https://bitbucket.org/eigen/eigen/src required login credentials.
  2. I tried updating the link to the comparable gitlab URL (see the .appveyor file in the most recent revision) in hopes that it was simply a download problem. It's still crying: "The system cannot find the path specified"

I can't tell if this is CMake or Appveyor that is angry and could use any light you can shed on this.

Reviewable status: 2 of 7 files reviewed, all discussions resolved (waiting on @DamrongGuoy and @sherm1)

Copy link
Contributor

@jamiesnape jamiesnape left a comment

Choose a reason for hiding this comment

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

Reviewable status: 2 of 7 files reviewed, all discussions resolved (waiting on @DamrongGuoy and @sherm1)


.appveyor.yml, line 43 at r6 (raw file):

            curl -L -o eigen-eigen-dc6cfdf9bcec.tar.gz https://gitlab.com/libeigen/eigen/-/archive/3.2.9/eigen-3.2.9.tar.gz &&
            cmake -E tar zxf eigen-eigen-dc6cfdf9bcec.tar.gz &&
            cd eigen-eigen-dc6cfdf9bcec &&
curl -LO https://gitlab.com/libeigen/eigen/-/archive/3.2.9/eigen-3.2.9.tar.gz
cmake -E tar zxf eigen-3.2.9.tar.gz
cd eigen-3.2.9

Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

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

Reviewed 5 of 5 files at r6.
Reviewable status: :shipit: complete! all files reviewed, all discussions resolved


include/fcl/geometry/shape/convex-inl.h, line 74 at r5 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

Surely the parentheses guarantees that it's 1 / 0 = inf? However, you're right, that isn't validated currently. I've added it as a note of things that aren't validated yet.

Er, right -- a perfectly nice 1/0. Nevermind!

Copy link
Contributor

@DamrongGuoy DamrongGuoy left a comment

Choose a reason for hiding this comment

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

Reviewable status: :shipit: complete! all files reviewed, all discussions resolved

Copy link
Contributor

@jamiesnape jamiesnape left a comment

Choose a reason for hiding this comment

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

Reviewable status: 6 of 7 files reviewed, 1 unresolved discussion (waiting on @SeanCurtis-TRI and @sherm1)


.appveyor.yml, line 43 at r7 (raw file):

            curl -LO https://gitlab.com/libeigen/eigen/-/archive/3.2.9/eigen-3.2.9.tar.gz &&
            cmake -E tar zxf eigen-3.2.9.tar.gz &&
            cd eigen-3.2.9

Missing &&

Copy link
Contributor Author

@SeanCurtis-TRI SeanCurtis-TRI left a comment

Choose a reason for hiding this comment

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

@jamiesnape Thanks for the help with windows.

The mac CI has failed a few times now. I note several things:

  1. It's constantly complaining about old XCode and old OSX.
  2. Inexplicably for both CMake and Git, it attempt to install older versions than are already installed. This seems to be largely glossed over with a "if you really mean it, do the following".
  3. However, eigen has cmake as a dependency and this attempts to build cmake and that leads to compilation error.
Last 15 lines from /Users/travis/Library/Logs/Homebrew/cmake/01.bootstrap:

mach_port_t __libcpp_thread_get_port() {

^

/Applications/Xcode.app/Contents/Developer/Toolchains/XcodeDefault.xctoolchain/usr/include/c++/v1/__threading_support:301:12: error: use of undeclared identifier 'pthread_mach_thread_np'

    return pthread_mach_thread_np(pthread_self());

           ^

clang++  -std=gnu++1z      -DCMAKE_BOOTSTRAP    -DCMake_HAVE_CXX_MAKE_UNIQUE=1   -I/private/tmp/cmake-20200825-59261-yspn6j/cmake-3.18.2/Bootstrap.cmk   -I/private/tmp/cmake-20200825-59261-yspn6j/cmake-3.18.2/Source   -I/private/tmp/cmake-20200825-59261-yspn6j/cmake-3.18.2/Source/LexerParser   -I/private/tmp/cmake-20200825-59261-yspn6j/cmake-3.18.2/Utilities/std   -I/private/tmp/cmake-20200825-59261-yspn6j/cmake-3.18.2/Utilities  -c /private/tmp/cmake-20200825-59261-yspn6j/cmake-3.18.2/Source/cmTarget.cxx -o cmTarget.o

Thoughts?

Reviewable status: 6 of 7 files reviewed, 1 unresolved discussion (waiting on @jamiesnape and @sherm1)


.appveyor.yml, line 43 at r6 (raw file):

Previously, jamiesnape (Jamie Snape) wrote…
curl -LO https://gitlab.com/libeigen/eigen/-/archive/3.2.9/eigen-3.2.9.tar.gz
cmake -E tar zxf eigen-3.2.9.tar.gz
cd eigen-3.2.9

Marvelous.


.appveyor.yml, line 43 at r7 (raw file):

Previously, jamiesnape (Jamie Snape) wrote…

Missing &&

Done.

@jamiesnape
Copy link
Contributor

jamiesnape commented Aug 25, 2020

Haven't looked into the error yet, the warnings are because you are explicitly choosing an ancient version of macOS that even Homebrew does not support.

Either:

  • delete the line
    osx_image: xcode9
    to get the default combination of macOS 10.13 and Xcode 9.4 (might still give a few warnings);
  • change that line to osx_image: xcode10.1 for macOS 10.13 and the last available Xcode for that OS version;
  • change that line to osx_image: xcode11.3 for macOS 10.14 and the last available Xcode for that OS version;
  • change that line to osx_image: xcode11.6 for macOS 10.15 and the latest stable Xcode.

Probably osx_image: xcode11.3 is nearest to Drake, if that matters.

Copy link
Contributor Author

@SeanCurtis-TRI SeanCurtis-TRI left a comment

Choose a reason for hiding this comment

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

Unless travis changed something this last weekend, I'd imagine the warnings were always there. Certainly, the errors don't seem related to the actual reported failure in bootstrapping cmake. Let me know when you have the chance to look.

Reviewable status: 6 of 7 files reviewed, 1 unresolved discussion (waiting on @jamiesnape and @sherm1)

@jamiesnape
Copy link
Contributor

Since the OS is so old, Homebrew has to build everything from source and there was a new version of CMake in the last week that no longer compiles. At that point Travis CI looks to be falling back to an old CMake since there is no error checking in any of the CI scripts.

Copy link
Contributor Author

@SeanCurtis-TRI SeanCurtis-TRI left a comment

Choose a reason for hiding this comment

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

Ok, I'm rolling advancing the mac CI into the PR with the linux CI. I'm testing it here and, assuming everything is happy, I'll rebase one more time here.

Reviewable status: 6 of 11 files reviewed, 1 unresolved discussion (waiting on @DamrongGuoy, @jamiesnape, and @sherm1)

@jamiesnape
Copy link
Contributor

Note, if you choose Xcode 9.4 your build will break again in a month or so when Apple releases macOS 11 and support is dropped for macOS 10.13.

Copy link
Contributor Author

@SeanCurtis-TRI SeanCurtis-TRI left a comment

Choose a reason for hiding this comment

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

What version of mac osx is comparable to linux bionic?

Reviewable status: 6 of 11 files reviewed, 1 unresolved discussion (waiting on @DamrongGuoy, @jamiesnape, and @sherm1)

Copy link
Contributor Author

@SeanCurtis-TRI SeanCurtis-TRI left a comment

Choose a reason for hiding this comment

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

("comparable" in the "contemporary" sense.)

Reviewable status: 6 of 11 files reviewed, 1 unresolved discussion (waiting on @DamrongGuoy, @jamiesnape, and @sherm1)

@jamiesnape
Copy link
Contributor

10.14 based on release date or the unreleased 11.0 based on end of support.

Copy link
Contributor Author

@SeanCurtis-TRI SeanCurtis-TRI left a comment

Choose a reason for hiding this comment

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

Thanks, @jamiesnape. I shook my magic eight ball and decided to bias "release date" over "end of support".

Reviewable status: 6 of 11 files reviewed, 1 unresolved discussion (waiting on @DamrongGuoy, @jamiesnape, and @sherm1)

The original implementation of supportConvex did a linear search across
all vertices. This makes the Convex mesh smarter to make the search for
the support vertex cheaper.

 - It builds an adjacency graph on all vertices upon construction.
 - It introduces the method findExtremeVertex Method which does a walk
   along the edges of the mesh to find the extreme vertex.
   - This is faster for large meshes but slower for small meshes.
   - Empirical data suggests around 32 vertices to be a good cut off.
   - This uses vertex count to determine which algorithm to use.
 - It also introduces initial validation of the mesh -- that validation
   absolutely necessary for the edge walking to provide a correct answer.
 - Several aspects of the implementation have been tested and tweaked
   for performance. See:
   - use of vector<int8_t> in Convex::findExtremeVertex
   - cache-friendly implementation of adjacency graph Convex::neighbors_.
Copy link
Contributor Author

@SeanCurtis-TRI SeanCurtis-TRI left a comment

Choose a reason for hiding this comment

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

CI has been updated and this PR has been rebased. The rebasing came with two changes:

  1. This PR has been added to the change log.
  2. Tests in test_convex.cpp were put back into the full exception message test (the regular expression functionality is sufficient in the upgraded CI).

PTAL (assuming this all passes CI).

Dismissed @jamiesnape from a discussion.
Reviewable status: 5 of 7 files reviewed, all discussions resolved (waiting on @DamrongGuoy and @sherm1)

Copy link
Contributor Author

@SeanCurtis-TRI SeanCurtis-TRI left a comment

Choose a reason for hiding this comment

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

@sherm1 @DamrongGuoy All of CI has passed. The changes are slight; I'll merge this tomorrow morning if you haven't responded.

Reviewable status: 5 of 7 files reviewed, all discussions resolved (waiting on @DamrongGuoy and @sherm1)

Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

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

Looks even better now!

Reviewed 3 of 3 files at r8.
Reviewable status: :shipit: complete! all files reviewed, all discussions resolved

@sherm1 sherm1 merged commit 0d98b83 into flexible-collision-library:master Aug 28, 2020
@SeanCurtis-TRI SeanCurtis-TRI deleted the PR_final_smarter_convex branch August 28, 2020 16:33
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants