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

Change convex shape constructor #338

Merged

Conversation

Levi-Armstrong
Copy link
Contributor

@Levi-Armstrong Levi-Armstrong commented Sep 17, 2018

Based on comments related to the convex shape to take std::shared_ptr<aligned_vector<Vector3<S>>> and std::shared_ptr<std::vector<int>> I decided to move forward and make the changes.

I originally went down the route of changing all Vector<S>* to const aligned_vector<Vector3<S>>& but this quickly took me down a rabbit hole. I have a different branch where I left off, so if this is desirable I will continue working it and create a pull request. This PR does the minimum to integrate the use of new types.


This change is Reviewable

Copy link
Contributor

@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 for tackling this. Obviously CI is angry -- I haven't looked into it; let me know if you'd like another pair of eyes on that. Otherwise, I have a number of design issues and requests where you've touched code and we have the chance to make it better than we found it.

Reviewed 8 of 8 files at r1.
Reviewable status: all files reviewed, 15 unresolved discussions (waiting on @Levi-Armstrong)

a discussion (no related file):
As I read through this PR, a concern comes to me. You're using at() on the vector access extensively. Generally, I'd like to stay away from that as it adds a cost with every access. However, given the esoteric structure defining faces, I can see that you'd use it because you have no guarantees that the contained ints are valid vertex indices, etc. So, the at() invocation protects you.

The logical alternative is to validate upon construction so that all of the operations can take for granted that things have been tested and it can blindly proceed without paying the cost on every operation. (And "validation" in this case merely means that all the indices are in bounds...nothing to do with confirming that this is truly convex.)

There's a gotcha, however. That is that the underlying geometric data is shared. That means after validating the data, anyone could go in and modify the data away from its validated state and the class would be fooled. However, we currently have this problem. We take num_faces as a construction argument. This is not shared. But the faces data is shared and someone could easily modify it so that num_faces is no longer valid w.r.t. the face data. So, by opting for shared data, Convex is at the mercy of whoever else has the data.

Recommendation:

  1. Add a "ValidateIndexes()` method that is called in the constructor that confirms all of the indices are valid (in bounds).
  2. Change accesses to rely on this validation (using [] instead of at()).
  3. Document the hell out of this -- explain that if anyone modifies the shared data after construction, there is undefined behavior. It is assumed that the vectors of vertex and face data never changes during the lifespan of this Convex instance.


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

  ///                       `num_faces` number of faces. See member
  ///                       documentation for details on encoding.
  Convex(const std::shared_ptr<aligned_vector<Vector3<S>>> &vertices, int num_faces, const std::shared_ptr<std::vector<int>> &faces);

nit: I don't believe aligned_vector is required. The eigen docs only stipulate it for vectorizable Eigen objects which doesn't include a Vector3. So, I'd suggest using a straight-up std::vector to facilitate users.


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

  ///                       `num_faces` number of faces. See member
  ///                       documentation for details on encoding.
  Convex(const std::shared_ptr<aligned_vector<Vector3<S>>> &vertices, int num_faces, const std::shared_ptr<std::vector<int>> &faces);

nit: The file has been modified to respect an 80-column limit (this is where we'll be going with the future style guide). In this case, it would be good if the modifications preserved this. So, this declaration should be two lines.


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

  ///                       `num_faces` number of faces. See member
  ///                       documentation for details on encoding.
  Convex(const std::shared_ptr<aligned_vector<Vector3<S>>> &vertices, int num_faces, const std::shared_ptr<std::vector<int>> &faces);

nit: The shared pointers should be pointers to const objects: e.g., const std::shared_ptr<const vector<Vector3<S>>& vertices; we want it clear that Convex isn't going to be writing to the vectors at all.


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

  /// @brief The total number of faces in the convex mesh.
  int num_faces;

nit: This should be const. And the same for vertices and faces.


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

  /// @brief get the vertices of some convex shape which can bound this shape in
  /// a specific configuration
  aligned_vector<Vector3<S>> getBoundVertices(const Transform3<S>& tf) const;

nit: same not on "alignment" as above.


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

  // alternative such as the centroid or bounding box center.
  Vector3<S> sum = Vector3<S>::Zero();
  std::accumulate(vertices->begin(), vertices->end(), sum);

BTW nice! Welcome to modern C++. :)


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

  this->aabb_local.max_.setConstant(-std::numeric_limits<S>::max());

  for(const auto &v : *vertices)

BTW This is purely my preference, but I'd request some curly braces on this. The alternative would be to put it all on a single line. But this is purely subjective opinion.


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

  S vol_times_six = 0;
  int face_encoding = faces->at(0);

BTW Why at() instead of []? In this particular case, zero seems like safe index.


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

  S vol_times_six = 0;
  int face_encoding = faces->at(0);

The variable face_encoding seems to be somewhat meaningless. It's not a pointer at all, so it no longer points to the beginning of a face encoding. It really is simply the vertex count for the current face.

I'd recommend with the type change, the semantics of the bookkeeping needs to shift. Generally, I would argue that this variable, besides being misnamed, is probably no longer relevant.

Obviously, this comment bleeds across to all of these volume-based quantities because of the redundancy of the code. Sorry about that.


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

  S vol_times_six = 0;
  int face_encoding = faces->at(0);
  int index = 1;

BTW I feel less strongly about this, but index is an incredibly generic name. There are multiple indices floating around (as witnessed by the at() invocations). As long as you're revisiting the semantics of this logic's variables, I'd love a better name. However, it wasn't immediately clear to me what that name should be. So, if you can't think of something better, index will do, I guess.


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

  for(const auto &v : *vertices)
    result.push_back(tf * v);

BTW See previous note on either single-line or bracket request.


include/fcl/geometry/shape/utility-inl.h, line 129 at r1 (raw file):

  static void run(const Shape& s, const Transform3<S>& tf, BV& bv)
  {
    auto convex_bound_vertices = s.getBoundVertices(tf);

nit: While I appreciate the desire to keep the line compact, I don't feel that the type of convex_bound_vertices is otherwise clear from the context and, therefore, would request the declared type.


include/fcl/geometry/shape/utility-inl.h, line 237 at r1 (raw file):

    AABB<S> bv_;
    for(const auto &curp : *(s.vertices))

nit: push the & left onto the auto, please.
nit: curp? An inscrutable abbreviation. Go ahead and use something a bit more easily consumable by the reader -- it's a small function, a descriptive name won't hurt it.


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

  maxdot = -CCD_REAL_MAX;

  for(const auto &curp : *(c->convex->vertices))

nit: I recognize that curp was part of the old code here, but I'd suggest we use this opportunity to give it a real name. :) (See previous not.)


include/fcl/narrowphase/detail/convexity_based_algorithm/minkowski_diff-inl.h, line 187 at r1 (raw file):

      S maxdot = - std::numeric_limits<S>::max();
      Vector3<S> bestv = Vector3<S>::Zero();
      for(const auto &curp : *(convex->vertices))

nit: Same again, re: curp.


include/fcl/narrowphase/detail/primitive_shape_algorithm/halfspace-inl.h, line 503 at r1 (raw file):

  S depth = std::numeric_limits<S>::max();

  for(const auto &curp : *(s1.vertices))

nit: And again.


include/fcl/narrowphase/detail/primitive_shape_algorithm/plane-inl.h, line 651 at r1 (raw file):

  S d_min = std::numeric_limits<S>::max(), d_max = -std::numeric_limits<S>::max();

  for(const auto &curp : *(s1.vertices))

nit ditto


test/geometry/shape/test_convex.cpp, line 97 at r1 (raw file):

  // The scale of the polytope to use with test tolerances.
  S scale() const { return scale_; }
  const std::shared_ptr<aligned_vector<Vector3<S>>>& points() const { return vertices_; }

nit: Another case where we want to preserve the 80-column limit -- throughout this whole file.


test/geometry/shape/test_convex.cpp, line 153 at r1 (raw file):

    while (i < static_cast<int>(polygons_->size())) {
      ++count;
      i += polygons_->at(i) + 1;

nit: swap at() for []?

@SeanCurtis-TRI SeanCurtis-TRI self-assigned this Sep 17, 2018
Copy link
Contributor

@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.

+@SeanCurtis-TRI for review

Reviewable status: all files reviewed, 15 unresolved discussions (waiting on @Levi-Armstrong)

@Levi-Armstrong
Copy link
Contributor Author

@SeanCurtis-TRI Should the member variables be made private and then provide methods for retrieving the data?

@SeanCurtis-TRI
Copy link
Contributor

In the absence of any data suggesting otherwise, I'd say yes. As I was going over the PR, I contemplated raising that issue. But since I'd quibbled about so much, and the public members was part of the FCL API already, I was willing to look the other way. But proper encapsulation would definitely be a good thing.

@Levi-Armstrong
Copy link
Contributor Author

Good. I am about to push another commit addressing all of the requested changes except the validate function which I am working on now. I remember now why I did not make it const objects because it required several function to be updated to allow the use of const objects. I have made the changes to allow the use of const objects for the convex shape.

Also I was not sure on how to best name the method for getting the number of faces. Let me know if you would like to name it something else.

Copy link
Contributor

@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.

Wow...there really was a const explosion here. :-/ I'll have to

Reviewed 14 of 14 files at r2.
Reviewable status: all files reviewed, 18 unresolved discussions (waiting on @Levi-Armstrong)


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

  ///
  /// @note: The %Convex geometry assumes that the input data %vertices and
  /// %faces does not change through the life of the object.

btw swap "does" for "do"


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

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

The variable face_encoding seems to be somewhat meaningless. It's not a pointer at all, so it no longer points to the beginning of a face encoding. It really is simply the vertex count for the current face.

I'd recommend with the type change, the semantics of the bookkeeping needs to shift. Generally, I would argue that this variable, besides being misnamed, is probably no longer relevant.

Obviously, this comment bleeds across to all of these volume-based quantities because of the redundancy of the code. Sorry about that.

This definitely reads better.


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

template <typename S>
Matrix3<S> Convex<S>::computeMomentofInertia() const {
  const std::vector<Vector3<S>> &vertices = *vertices_;

nit: Ampersand connected to the type and not the symbol.


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

    }

    face_index += vertex_count + 2;

nit: this 2 really surprises me. Every face is defined by vertex_count + 1 ints (the count and each vertex index). So, the stride between one face and the next should be vertex_count + 1. Am I missing something?


include/fcl/geometry/shape/utility-inl.h, line 237 at r1 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

nit: push the & left onto the auto, please.
nit: curp? An inscrutable abbreviation. Go ahead and use something a bit more easily consumable by the reader -- it's a small function, a descriptive name won't hurt it.

nit: swap vertice for vertex. (Applies multiple times.)


include/fcl/math/geometry.h, line 128 at r2 (raw file):

FCL_EXPORT
void getRadiusAndOriginAndRectangleSize(
    const Vector3<S>* const ps,

I'm assuming this became necessary because of the const-ness introduced in Convex, yes?


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

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

nit: I recognize that curp was part of the old code here, but I'd suggest we use this opportunity to give it a real name. :) (See previous not.)

Should probably be vertex instead of vertice.


test/geometry/shape/test_convex.cpp, line 98 at r2 (raw file):

  S scale() const { return scale_; }
  const std::shared_ptr<const std::vector<Vector3<S>>>& points() const {
    return vertices_;

This is your CI error (well, here and the next). The problem is that vertices_ is of type std::shared_ptr<std::vector<Vector3<S>>> (note the missing const on the vector. So, this implicitly creates a new shared_ptr from the old shared_ptr and then attempts to return a reference to that temporary.

Given that it's a shared pointer, you might consider killing the reference on the return type and simply return a shared pointer. The problem is that I don't know that it will truly have the same underlying vector. I'll play a little and get back to you. I may have been premature in requesting const data -- I have limited experience with shared_ptr.

Copy link
Contributor

@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.

Reviewable status: 12 of 14 files reviewed, 18 unresolved discussions (waiting on @SeanCurtis-TRI and @Levi-Armstrong)


test/geometry/shape/test_convex.cpp, line 98 at r2 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

This is your CI error (well, here and the next). The problem is that vertices_ is of type std::shared_ptr<std::vector<Vector3<S>>> (note the missing const on the vector. So, this implicitly creates a new shared_ptr from the old shared_ptr and then attempts to return a reference to that temporary.

Given that it's a shared pointer, you might consider killing the reference on the return type and simply return a shared pointer. The problem is that I don't know that it will truly have the same underlying vector. I'll play a little and get back to you. I may have been premature in requesting const data -- I have limited experience with shared_ptr.

After a quick experiment, it looks like this would work:

return std::unique_ptr<const std::vector<Vector3<S>>>>(vertices_);

I did a quick test and it appears that it properly shares the underlying structure.

Copy link
Contributor

@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.

Reviewed 2 of 2 files at r3.
Reviewable status: all files reviewed, 18 unresolved discussions (waiting on @Levi-Armstrong)

a discussion (no related file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

As I read through this PR, a concern comes to me. You're using at() on the vector access extensively. Generally, I'd like to stay away from that as it adds a cost with every access. However, given the esoteric structure defining faces, I can see that you'd use it because you have no guarantees that the contained ints are valid vertex indices, etc. So, the at() invocation protects you.

The logical alternative is to validate upon construction so that all of the operations can take for granted that things have been tested and it can blindly proceed without paying the cost on every operation. (And "validation" in this case merely means that all the indices are in bounds...nothing to do with confirming that this is truly convex.)

There's a gotcha, however. That is that the underlying geometric data is shared. That means after validating the data, anyone could go in and modify the data away from its validated state and the class would be fooled. However, we currently have this problem. We take num_faces as a construction argument. This is not shared. But the faces data is shared and someone could easily modify it so that num_faces is no longer valid w.r.t. the face data. So, by opting for shared data, Convex is at the mercy of whoever else has the data.

Recommendation:

  1. Add a "ValidateIndexes()` method that is called in the constructor that confirms all of the indices are valid (in bounds).
  2. Change accesses to rely on this validation (using [] instead of at()).
  3. Document the hell out of this -- explain that if anyone modifies the shared data after construction, there is undefined behavior. It is assumed that the vectors of vertex and face data never changes during the lifespan of this Convex instance.

On a completely different subject -- I presume you're using github to do the review, yes? There's a "Reviewable" link in the PR and I highly recommend trying it out. It's a much cleaner interface for having conversations and tracking issues. Let me know if you want a run down on it.


Copy link
Contributor Author

@Levi-Armstrong Levi-Armstrong 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, 18 unresolved discussions (waiting on @Levi-Armstrong)


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

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

nit: this 2 really surprises me. Every face is defined by vertex_count + 1 ints (the count and each vertex index). So, the stride between one face and the next should be vertex_count + 1. Am I missing something?

Your right error on my part. Late night. :)


include/fcl/math/geometry.h, line 128 at r2 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

I'm assuming this became necessary because of the const-ness introduced in Convex, yes?

I believe so, but some I updated for consistency.

@Levi-Armstrong
Copy link
Contributor Author


test/geometry/shape/test_convex.cpp, line 98 at r2 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

After a quick experiment, it looks like this would work:

return std::unique_ptr<const std::vector<Vector3<S>>>>(vertices_);

I did a quick test and it appears that it properly shares the underlying structure.

Thank you for pointing me to the right file. I should not have been returning const reference to the shared pointer for the Polytope Class.

@Levi-Armstrong
Copy link
Contributor Author

Ok, so everything builds now but tests are failing so I will look into this further.

@DamrongGuoy
Copy link
Contributor


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

  ///                       `num_faces` number of faces. See member
  ///                       documentation for details on encoding.
  Convex(const std::shared_ptr<const std::vector<Vector3<S>>>& vertices,

BTW, since we are changing API of the constructor, should we consider backward compatibility or communicate this change to users? We don't want to break the build of existing users. A backward compatibility could be as simple as keeping the older constructor in parallel with the newer one with a warning.

For me, I'm writing a code in Drake to create fcl::Convex using the older constructor that I'll be happy to switch to the newer better one when it's available.

@SeanCurtis-TRI
Copy link
Contributor

That is an excellent point. However, I saw we proceed for the following reasons:

  1. This doesn't change the last releases. So, people who are using a fixed release will be unaffected.
  2. We've already touched the Convex interface (at least construction) recently in master and have heard no complaints. So, this follow up change is probably safe.

@Levi-Armstrong
Copy link
Contributor Author

@SeanCurtis-TRI I found a few issues that I introduce which have been resolved but I can't figure out what I have changed that would causing a few of the tests to fail. Do you have any insight?

@Levi-Armstrong
Copy link
Contributor Author

@SeanCurtis-TRI I did some more investigating and I am still not sure why the two test are failing using float types.

@Levi-Armstrong
Copy link
Contributor Author

I decided to try the original function code where I convert the std::vector to c_array to see if maybe I made an error translating the function but I get the same test failures. Not sure what to do now. Overall the error is still very small and it is scaling the test tolerance based on the volume size which does make sense but is it an accurate representation of the expected error?

  std::vector<Vector3<S>> temp_vertices(*vertices_);
  std::vector<int> temp_faces(*faces_);
  Vector3<S>* vertices = &temp_vertices[0];
  int *face_encoding = &temp_faces[0];
  int *index = face_encoding + 1;
  for(int i = 0; i < num_faces_; ++i) {
    const int vertex_count = *face_encoding;
    Vector3<S> face_center = Vector3<S>::Zero();

    // TODO(SeanCurtis-TRI): While this is general, this is inefficient. If the
    // face happens to be a triangle, this does 3X the requisite work.
    // If the face is a 4-gon, then this does 2X the requisite work.
    // As N increases in the N-gon this approach's inherent relative penalty
    // shrinks. Ideally, this should at least key on 3-gon and 4-gon before
    // falling through to this.

    // Compute the center of the polygon.
    for(int j = 0; j < vertex_count; ++j)
      face_center += vertices[index[j]];
    face_center = face_center * (1.0 / vertex_count);

    // TODO(SeanCurtis-TRI): Because volume serves as the weights for
    // center-of-mass an inertia computations, it should be refactored into its
    // own function that can be invoked by providing three vertices (the fourth
    // being the origin).

    // Compute the volume of tetrahedron formed by the vertices on one of the
    // polygon's edges, the center point, and the shape's frame's origin.
    const Vector3<S>& v3 = face_center;
    for(int j = 0; j < vertex_count; ++j) {
      int e_first = index[j];
      int e_second = index[(j + 1) % vertex_count];
      const Vector3<S>& v1 = vertices[e_first];
      const Vector3<S>& v2 = vertices[e_second];
      S d_six_vol = (v1.cross(v2)).dot(v3);
      vol += d_six_vol;
    }

    face_encoding += vertex_count + 1;
    index = face_encoding + 1;
  }

  return vol / 6;
}

@SeanCurtis-TRI
Copy link
Contributor

I didn't get a chance to look at it today. I'll look at it first thing in the morning to see if I can come up with anything.

Copy link
Contributor

@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've found the problem.

tl;dr: the introduction of the shared pointer in the Polytope class turned a deep copy into a shallow copy so the underlying polytope vertices were gradually corrupting with each test.

This patch addresses the issues:

diff --git a/test/geometry/shape/test_convex.cpp b/test/geometry/shape/test_convex.cpp
index efb75d7..d15a5f9 100644
--- a/test/geometry/shape/test_convex.cpp
+++ b/test/geometry/shape/test_convex.cpp
@@ -38,6 +38,7 @@
 
 #include "fcl/geometry/shape/convex.h"
 
+#include <memory>
 #include <vector>
 
 #include <Eigen/StdVector>
@@ -79,23 +80,28 @@ struct ScalarString<float> {
 template <typename S>
 class Polytope {
  public:
-  explicit Polytope(S scale) : scale_(scale)
-  {
-    vertices_.reset(new std::vector<Vector3<S>>());
-    polygons_.reset(new std::vector<int>());
-  }
-
-  virtual int face_count() const = 0;
-  virtual int vertex_count() const = 0;
-  virtual S volume() const = 0;
-  virtual Vector3<S> com() const = 0;
-  virtual Matrix3<S> principal_inertia_tensor() const = 0;
-  virtual std::string description() const = 0;
-
-  // The scale of the polytope to use with test tolerances.
-  S scale() const { return scale_; }
-  std::shared_ptr<const std::vector<Vector3<S>>> points() const {
-    return vertices_;
+   explicit Polytope(S scale)
+       : vertices_(std::make_shared<std::vector<Vector3<S>>>()),
+         polygons_(std::make_shared<std::vector<int>>()), scale_(scale) {}
+
+   Polytope(const Polytope &other)
+       : vertices_(std::make_shared<std::vector<Vector3<S>>>(
+             other.vertices_->begin(), other.vertices_->end())),
+         polygons_(std::make_shared<std::vector<int>>(other.polygons_->begin(),
+                                                      other.polygons_->end())),
+         scale_(other.scale_) {}
+
+   virtual int face_count() const = 0;
+   virtual int vertex_count() const = 0;
+   virtual S volume() const = 0;
+   virtual Vector3<S> com() const = 0;
+   virtual Matrix3<S> principal_inertia_tensor() const = 0;
+   virtual std::string description() const = 0;
+
+   // The scale of the polytope to use with test tolerances.
+   S scale() const { return scale_; }
+   std::shared_ptr<const std::vector<Vector3<S>>> points() const {
+     return vertices_;
   }
   std::shared_ptr<const std::vector<int>> polygons() const {
     return polygons_;
@@ -164,7 +170,7 @@ class Polytope {
  private:
   std::shared_ptr<std::vector<Vector3<S>>> vertices_;
   std::shared_ptr<std::vector<int>> polygons_;
-  S scale_{1};
+  S scale_{};
 };
 
 // A simple regular tetrahedron with edges of length `scale` centered on the

Go ahead and add this to the PR and I'll do another full review.

Reviewable status: 6 of 14 files reviewed, 18 unresolved discussions (waiting on @SeanCurtis-TRI and @Levi-Armstrong)

Copy link
Contributor

@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.

For some inexplicable reason, that diff ended up much larger than it should be -- including more than I felt changed. This patch is more concise to what actually needs to change.

diff --git a/test/geometry/shape/test_convex.cpp b/test/geometry/shape/test_convex.cpp
index efb75d7..765a72d 100644
--- a/test/geometry/shape/test_convex.cpp
+++ b/test/geometry/shape/test_convex.cpp
@@ -38,6 +38,7 @@
 
 #include "fcl/geometry/shape/convex.h"
 
+#include <memory>
 #include <vector>
 
 #include <Eigen/StdVector>
@@ -79,11 +80,16 @@ struct ScalarString<float> {
 template <typename S>
 class Polytope {
  public:
-  explicit Polytope(S scale) : scale_(scale)
-  {
-    vertices_.reset(new std::vector<Vector3<S>>());
-    polygons_.reset(new std::vector<int>());
-  }
+   explicit Polytope(S scale)
+       : vertices_(std::make_shared<std::vector<Vector3<S>>>()),
+         polygons_(std::make_shared<std::vector<int>>()), scale_(scale) {}
+
+   Polytope(const Polytope &other)
+       : vertices_(std::make_shared<std::vector<Vector3<S>>>(
+             other.vertices_->begin(), other.vertices_->end())),
+         polygons_(std::make_shared<std::vector<int>>(other.polygons_->begin(),
+                                                      other.polygons_->end())),
+         scale_(other.scale_) {}
 
   virtual int face_count() const = 0;
   virtual int vertex_count() const = 0;
@@ -164,7 +170,7 @@ class Polytope {
  private:
   std::shared_ptr<std::vector<Vector3<S>>> vertices_;
   std::shared_ptr<std::vector<int>> polygons_;
-  S scale_{1};
+  S scale_{};
 };
 
 // A simple regular tetrahedron with edges of length `scale` centered on the

Reviewable status: 6 of 14 files reviewed, 18 unresolved discussions (waiting on @SeanCurtis-TRI and @Levi-Armstrong)

@Levi-Armstrong
Copy link
Contributor Author

That make since. I am curious, how did you track this down?

The test is now passing and thanks for the help tracking this down. It looks like CI has an issue with using std::accumulate on clang XCode.

@SeanCurtis-TRI
Copy link
Contributor

Once I'd convinced myself the std::accumulate wasn't making a difference, the only thing I could suppose is that somehow the order of operations was different. So, I applied logging to the volume computation that would spew out indices, vertex values, volume values, etc, during its computation. After I did that, I wanted to reduce the spew and only do the single test that was failing (with the cube, that is). And I found that the test in question had different vertex values when I ran it in sequence vs running it alone. That's when I realized that the values were being changed which immediately led to the shared-ptr, deep/shallow copy shenanigans.

If we have to, to appease the Mac gods, we can just go back to a for loop. Not the end of the world.

@Levi-Armstrong
Copy link
Contributor Author

@SeanCurtis-TRI I removed the use of std::accumulate and CI is happy now.

Copy link
Contributor Author

@Levi-Armstrong Levi-Armstrong 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 14 files reviewed, 8 unresolved discussions (waiting on @SeanCurtis-TRI and @Levi-Armstrong)


include/fcl/math/geometry.h, line 128 at r2 (raw file):

Previously, Levi-Armstrong (Levi Armstrong) wrote…

I believe so, but some I updated for consistency.

Done.


test/geometry/shape/test_convex.cpp, line 98 at r2 (raw file):

Previously, Levi-Armstrong (Levi Armstrong) wrote…

Thank you for pointing me to the right file. I should not have been returning const reference to the shared pointer for the Polytope Class.

Done.

@Levi-Armstrong
Copy link
Contributor Author

a discussion (no related file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

On a completely different subject -- I presume you're using github to do the review, yes? There's a "Reviewable" link in the PR and I highly recommend trying it out. It's a much cleaner interface for having conversations and tracking issues. Let me know if you want a run down on it.

I have been going through the process but would be interested to know how best to use it. I went through and selected the acknowledged, Resolved, or Done.


Copy link
Contributor

@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.

The penultimate pass is done. With everything happy in CI, I took another big picture pass on things and ended up accumulating a few minor lint items.

Reviewed 6 of 8 files at r4, 1 of 2 files at r5, 1 of 1 files at r6.
Reviewable status: all files reviewed, 9 unresolved discussions (waiting on @SeanCurtis-TRI and @Levi-Armstrong)

a discussion (no related file):

Previously, Levi-Armstrong (Levi Armstrong) wrote…

I have been going through the process but would be interested to know how best to use it. I went through and selected the acknowledged, Resolved, or Done.

Some random reviewable thoughts:

Comments beginning with "btw" or "fyi" are things that I note in passing that can simply be fixed without my follow up. If you click "Acknowledge" or type "done", the issue immediately closes. I tend to use these for suggestions but not actual defects, per se.
Comments beginning with "nit" or "minor" are slightly elevated; it requires me to actively acknowledge a change in the code. I'll do this for minor stuff (spelling, formatting, cosmetic artifacts, etc.)
Comments that don't have any of the previous prefixes are usually issues that may require discussion.

The nice thing about reviewable is that it does a reasonably good job of tracking the revisions of the code, tying comments to them, and keeping you abreast of where the open issues are.


a discussion (no related file):
New thought: You should probably document this API change in the README.md file so it's captured for the next release.



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

Previously, DamrongGuoy (Damrong Guoy) wrote…

BTW, since we are changing API of the constructor, should we consider backward compatibility or communicate this change to users? We don't want to break the build of existing users. A backward compatibility could be as simple as keeping the older constructor in parallel with the newer one with a warning.

For me, I'm writing a code in Drake to create fcl::Convex using the older constructor that I'll be happy to switch to the newer better one when it's available.

The API change is going into the head of master -- there is no release that this affects. This API change will go into the next release. Users drawing from a public release/tag will be unaffected.


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

  NODE_TYPE getNodeType() const override;

  /// @brief Get the vertex positions in the geometry's frame G.

nit: meta note: The style guide we're pushing to is the google style guide. As such, function documentation should be of the descriptive form and not the "imperative" form. I.e., "Gets the vertex positions..." instead of "Get the...."


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

  /// @brief Get the vertex positions in the geometry's frame G.
  const std::shared_ptr<const std::vector<Vector3<S>>>& getVertices() const {

nit: This should simply return a const reference to the vertices:

const std::vector<Vector3<S>>& getVertices() const { return *vertices_; }

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

  ///    3. the indices of the face correspond to a proper counter-clockwise
  ///       ordering.
  const std::shared_ptr<const std::vector<int>>& getFaces() const {

nit: This should simply return a const reference to the faces:

const std::vector<int>& getFaces() const { return *faces_; }

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

private:
  const std::shared_ptr<const std::vector<Vector3<S>>> vertices_;
  int num_faces_;

nit: This should also be const.


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

//==============================================================================
template <typename S>
Convex<S>::Convex(const std::shared_ptr<const std::vector<Vector3<S>>>& vertices,

nit: line length > 80 columns.


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

    for(int j = 1; j <= vertex_count; ++j) {
      int e_first = faces[face_index + j];
      int e_second = faces[face_index + (j % vertex_count) + 1];

btw: This is an odd enough looking + 1, that it's worth putting a note in here as to why it's here. That way future developers don't look at this and think, "Wait...is that right?" (And in the subsequent copies below, as well.)


include/fcl/geometry/shape/utility-inl.h, line 253 at r6 (raw file):

  static void run(const Convex<S>& s, const Transform3<S>& tf, OBB<S>& bv)
  {
    fit(s.getVertices()->data(), (int)s.getVertices()->size(), bv);

nit: replace (int)... with static_cast<int>(...). Although the former is more compact, it is a really big hammer that does a poor job of communicating limited intent. As an optional variation, you could add int Convex::num_vertices() const to the Convex shape and bury the static cast there.


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

  maxdot = -CCD_REAL_MAX;

  for(const auto& vertex : *(c->convex->getVertices()))

btw: missing space between for ( (although, that was there before you got here. Still, as long as we're here. :))


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

  for(const auto& vertex : *(c->convex->getVertices()))
  {
    ccdVec3Set(&p, vertex[0] - center[0], vertex[1] - center[1], vertex[2] - center[2]);

nit: line length

Copy link
Contributor Author

@Levi-Armstrong Levi-Armstrong 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, 9 unresolved discussions (waiting on @Levi-Armstrong)


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

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

nit: This should simply return a const reference to the vertices:

const std::vector<Vector3<S>>& getVertices() const { return *vertices_; }

My thought process was if the shared point was returned you easily construct another object using the same shared data. Then the user could de-reference the pointer to get the object if needed.


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

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

nit: This should simply return a const reference to the faces:

const std::vector<int>& getFaces() const { return *faces_; }

Same as above.


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

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

nit: This should also be const.

Agree

Copy link
Contributor

@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.

Reviewable status: all files reviewed, 9 unresolved discussions (waiting on @Levi-Armstrong and @SeanCurtis-TRI)


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

Previously, Levi-Armstrong (Levi Armstrong) wrote…

My thought process was if the shared point was returned you easily construct another object using the same shared data. Then the user could de-reference the pointer to get the object if needed.

I can see that. I have two thoughts:

  1. It provides a bit of a counter-intuitive interface for all of the other code that is accessing the vertices/faces
  2. The best way to accomplish that would be to use the copy constructor.

Copy link
Contributor

@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.

You've got a couple of minor things here -- and you'll need to rebase on master.

Reviewable status: all files reviewed, 9 unresolved discussions (waiting on @Levi-Armstrong and @SeanCurtis-TRI)

@Levi-Armstrong
Copy link
Contributor Author

Levi-Armstrong commented Oct 9, 2018

Sorry I have been out on vacation. I will work on this today.

Copy link
Contributor Author

@Levi-Armstrong Levi-Armstrong 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: 7 of 14 files reviewed, 2 unresolved discussions (waiting on @SeanCurtis-TRI and @Levi-Armstrong)

a discussion (no related file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

New thought: You should probably document this API change in the README.md file so it's captured for the next release.

Do you have an example of how you would like it documented?


Copy link
Contributor

@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.

And now, I'm a week later. :)

Thanks for scrubbing alot of the formatting. You'll need to rebase this on master.

Reviewed 7 of 7 files at r7.
Reviewable status: all files reviewed, 3 unresolved discussions (waiting on @Levi-Armstrong and @SeanCurtis-TRI)

a discussion (no related file):

Previously, Levi-Armstrong (Levi Armstrong) wrote…

Do you have an example of how you would like it documented?

I realize I wrote "README.md", but what I really meant was "CHANGELOG.md". Oops. What I'd recommend is going into the line that specifically refers to "Simplified Convex class..." and simply add a reference to this PR after the one already there.



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

  ///
  /// @note: The %Convex geometry assumes that the input data %vertices and
  /// %faces does not change through the life of the object.

nit: "do" was correct; "data" is plural or "vertices and faces" is plural.


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

    const Vector3<S>& v3 = face_center;
    for (int j = 1; j <= vertex_count; ++j) {
      // Each edge of the polygon is defined where faces[face_index + j] is

BTW I had a passing thought. I leave it up to you on how you want to respond.

In this implementation, face's vertex indices are functionally 1-indexed (instead of the more typical zero-indexed.) (hence j ∈ [1, vertex_count]. All of the weirdness in the code (that you try to explain in the documentation) arises from the fact. You might try the following to alleviate the awkwardness:

const Vector3<S>& v3 = face_center;
const int vertex_base = face_index + 1;
for (int j = 0; j < vertex_count; ++j) {
  int e_first = faces[vertex_base + j];
  int e_second = faces[vertex_base + (j + 1) % vertex_count];
  ...
}

or

const Vector3<S>& v3 = face_center;
const int* face_vertices = faces.data() + (face_index + 1);
for (int j = 0; j < vertex_count; ++j) {
  int e_first = face_vertices[ j];
  int e_second = face_vertices[ (j + 1) % vertex_count];
  ...
}

Either of those might remove the necessity of the documentation by making the code itself more conventional.


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

  {
    ccdVec3Set(&p, vertex[0] - center[0], vertex[1] - center[1],
        vertex[2] - center[2]);

BTW Typically, in the google style (via clang-format), a broken list of function parameters would align on the first character of the first parameter:

  ccdVec3Set(&p, vertex[0] - center[0], vertex[1] - center[1],
             vertex[2] - center[2]);

(Same below.)

@Levi-Armstrong
Copy link
Contributor Author

I plan to make the remaining changes this week and I apologize for the delay.

Copy link
Contributor

@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.

I look forward to it. And given my delay in getting you feedback, I'm not exactly in a position to throw stones. :)

Reviewable status: all files reviewed, 3 unresolved discussions (waiting on @Levi-Armstrong)

@Levi-Armstrong
Copy link
Contributor Author

@SeanCurtis-TRI I believe the requested changes have been resolved.

Copy link
Contributor

@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.

Huzzah! Thanks for doing this.

Reviewed 3 of 3 files at r8.
Reviewable status: all files reviewed, 2 unresolved discussions (waiting on @Levi-Armstrong)

Copy link
Contributor

@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.

Reviewable status: all files reviewed, 1 unresolved discussion (waiting on @Levi-Armstrong)

a discussion (no related file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

I realize I wrote "README.md", but what I really meant was "CHANGELOG.md". Oops. What I'd recommend is going into the line that specifically refers to "Simplified Convex class..." and simply add a reference to this PR after the one already there.

This is the one thing missing -- if you want to give me push permissions on your branch, I can make the change. Or, if you add it to the change log, then we'll be good.


@Levi-Armstrong
Copy link
Contributor Author

Allow edits from maintainer is enabled.

Copy link
Contributor

@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.

Reviewed 1 of 1 files at r9, 1 of 1 files at r10.
Reviewable status: :shipit: complete! all files reviewed, all discussions resolved

a discussion (no related file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

This is the one thing missing -- if you want to give me push permissions on your branch, I can make the change. Or, if you add it to the change log, then we'll be good.

Done


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.

3 participants