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

Add primitive box-sphere collision and distance query #316

Conversation

SeanCurtis-TRI
Copy link
Contributor

@SeanCurtis-TRI SeanCurtis-TRI commented Jul 24, 2018

By default, the GJK solver was being used for performing distance queries between box's and spheres. For small features, the answer was being dominated by the iterative tolerance and producing wildly problematic values. The logical thing to do is to perform sphere-box collisions using knowledge of the primitives.

This commit adds the following:

  • A new test illustrating the error of GJK is used (see test_fcl_sphere_box.cpp)
  • Borrows the CompareMatrices functionality from Drake and adds it to FCL.
  • Adds the custom sphere-box collision (sphere_box.h and sphere_box-inl.h)
  • Adds extensive unit tests on the custom algorithm.
  • Ties the custom algorithm into the libccd and indep GJK solvers.

This PR also includes an independent commit that allows the GJK solvers to be built with float.
This PR doesn't include the distance version of the test in test_fcl_sphere_box.cpp. Instead, it contains a TODO.

Sorry for the size, you can chalk that up to the tests (more than half).

Category            added  modified  removed  
----------------------------------------------
code                780    1         0        
comments            503    4         0        
blank               157    0         0        
----------------------------------------------
TOTAL               1440   5         0  

This change is Reviewable

Literal values were defined in box-box primitve and being interpreted as
doubles. This caused errors when compiling with S = float. This fix
addresses that issue.
@SeanCurtis-TRI SeanCurtis-TRI force-pushed the PR_box_sphere_collision branch 5 times, most recently from 3328768 to f44d931 Compare July 24, 2018 17:39
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.

+@amcastro-tri

Reviewable status: 0 of 12 files reviewed, all discussions resolved

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.

Reviewable status: 0 of 12 files reviewed, 1 unresolved discussion (waiting on @amcastro-tri)


test/narrowphase/detail/primitive_shape_algorithm/test_sphere_box.cpp, line 261 at r2 (raw file):

  // penetration depth is the radius *plus* the amount below h/2 the center lies
  // (i.e., h - cz + radius). The position is half the penetration depth below
  // the +z face.

It would probably be better if this test included a version nearest all six faces. This might pass because the underlying function mistakenly favors the +z direction and panders to this test.

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.

Blech! Mass CI failure....

Reviewable status: 0 of 12 files reviewed, 1 unresolved discussion (waiting on @amcastro-tri)

Copy link
Contributor

@amcastro-tri amcastro-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 r1, 2 of 11 files at r2.
Reviewable status: 3 of 12 files reviewed, 4 unresolved discussions (waiting on @SeanCurtis-TRI and @amcastro-tri)


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h, line 78 at r2 (raw file):

 @param box            The box geometry.
 @param X_FB           The pose of the box B in the common frame F.
 @param contacts[out]  (optional) If the shapes collide, the contact witness

BTW, (optional) means nullptr?


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h, line 78 at r2 (raw file):

 @param box            The box geometry.
 @param X_FB           The pose of the box B in the common frame F.
 @param contacts[out]  (optional) If the shapes collide, the contact witness

Could you expand on “contact witness”? Is that a term of art or an FCL term? Or...?


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h, line 78 at r2 (raw file):

 @param box            The box geometry.
 @param X_FB           The pose of the box B in the common frame F.
 @param contacts[out]  (optional) If the shapes collide, the contact witness

On output, what size is contacts expected to have? Will it be resized for me?


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h, line 83 at r2 (raw file):

 @tparam S The scalar parameter (must be a valid Eigen scalar).  */
template <typename S>
FCL_EXPORT bool sphereBoxIntersect(const Sphere<S> &sphere,

Nit: is FCL’s convention to place & and * next to the variable?


src/narrowphase/detail/primitive_shape_algorithm/sphere_box.cpp, line 48 at r2 (raw file):

template bool
sphereBoxIntersect(const Sphere<double>& sphere, const Transform3<double>& X_FS,
                   const Box<double>& box, const Transform3<double>& X_FB,

BTW I see the & next to the type here but not in the header. Is there a convention?

@SeanCurtis-TRI SeanCurtis-TRI force-pushed the PR_box_sphere_collision branch 2 times, most recently from 6faea1f to 855d69d Compare July 24, 2018 20:54
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.

Reviewable status: 2 of 14 files reviewed, 3 unresolved discussions (waiting on @amcastro-tri and @SeanCurtis-TRI)


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h, line 78 at r2 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

On output, what size is contacts expected to have? Will it be resized for me?

Modified comment. PTAL


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h, line 78 at r2 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

Could you expand on “contact witness”? Is that a term of art or an FCL term? Or...?

Removed the term.


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h, line 78 at r2 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

BTW, (optional) means nullptr?

Documentation elaborated. PTAL


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h, line 83 at r2 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

Nit: is FCL’s convention to place & and * next to the variable?

Done Dammit -- Clion keeps moving those. It looks like if I clang-format the file, it's accessing some horrible settings. So, if I don't selectively clang-format in FCL, I get those jumping all over the place.

@SeanCurtis-TRI SeanCurtis-TRI force-pushed the PR_box_sphere_collision branch 5 times, most recently from ff2111c to f1bbef5 Compare July 25, 2018 00:02
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.

+(Status: on hold) Don't review; I'm currently jumping through hoops trying to run down a CI failure. When I find it, I'll clean up the PR and remove the status.

Reviewable status: 2 of 14 files reviewed, 3 unresolved discussions (waiting on @amcastro-tri)

@SeanCurtis-TRI SeanCurtis-TRI force-pushed the PR_box_sphere_collision branch 2 times, most recently from d36c4a2 to 851d0df Compare July 25, 2018 14:35
Copy link
Contributor

@amcastro-tri amcastro-tri left a comment

Choose a reason for hiding this comment

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

another pass, only through the "easy files".

Reviewed 4 of 11 files at r2, 3 of 8 files at r3.
Reviewable status: 9 of 14 files reviewed, 13 unresolved discussions (waiting on @amcastro-tri and @SeanCurtis-TRI)


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box-inl.h, line 61 at r2 (raw file):

// Helper function for box-sphere queries. Given a box defined in its canonical
// frame (i.e., aligned to the axes and centered on the origin) and a query

Nit: frame B was not defined. Shortcut, “...its canonical frame B....”


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box-inl.h, line 73 at r2 (raw file):

template <typename S>
bool nearestPointInBox(const Vector3<S> &size, const Vector3<S> &p_BQ,
                       Vector3<S> &p_BN) {

Nit: no GSG I pressume? And no intention on adopting it either right? I just thought the output in the header file were pointers and that probably u’d like to match that here?


test/eigen_matrix_compare.h, line 35 at r4 (raw file):

 */

/** @author Sean Curtis */

regarding the license, is it ok to copy it into a file grabbed from somewhere else? maybe question form @sherm1

nit: does the author tag applies given the disclaimer below?


test/test_fcl_collision.cpp, line 831 at r4 (raw file):

// Tests the tolerance value in the CollisionRequest, confirming that it
// propagates down to the solution. It creates a box and sphere and positions

"Tests the tolerance value in the CollisionRequest, confirming that it propagates down to the solution. It creates a box and sphere and positions"

I see why you remove this test now (given sphere-box now is analytic). However, that the tolerance propagates down the pipeline is not tested anymore? maybe a TODO would suffice.


test/test_fcl_sphere_box.cpp, line 78 at r3 (raw file):

//  - One contact *should* be reported,
//  - Penetration depth δ should be: radius - (sz - h / 2),
//  - Contact point should be at: [sx, sy, h / 2 - δ / 2], and

δ / 2? is than an FCL convention? so contact point is always half way of the total penetration?


test/test_fcl_sphere_box.cpp, line 106 at r3 (raw file):

  const Vector3<S> half_size{w / 2, d / 2, h / 2};
  const Real r = 0.0015;
  CollisionGeometryPtr_t sphere_geometry(new fcl::Sphere<S>(r));

BTW std::make_shared()?


test/test_fcl_sphere_box.cpp, line 134 at r3 (raw file):

  const Vector3<S> expected_normal = -Vector3<S>::UnitZ();
  const int one_contact = 1;
  const bool enable_contact = true;

the docs on this parameter are pretty much lacking. Could you add here a one liner about what this parameter is for?


test/test_fcl_sphere_box.cpp, line 135 at r3 (raw file):

  const int one_contact = 1;
  const bool enable_contact = true;
  fcl::CollisionRequest<S> collision_request(one_contact, enable_contact);

BTW for my own education only, when would I want the paramter num_max_contacts to be different from one and what would it accomplish?


test/test_fcl_sphere_box.cpp, line 142 at r3 (raw file):

  // distance half_size.
  const std::vector<Real> x_values{
      -half_size(0) + r,  -half_size(0) * S(0.5), -eps, 0, eps,

could you comment why:

  • half_size + r? would the test work if I use an x value of just half_size?
  • Why those values close to zero? (-eps, 0, eps). What's special about them?

test/test_fcl_sphere_box.cpp, line 154 at r3 (raw file):

      auto evaluate_collision = [&collision_request, &X_WS, &one_contact](
          const fcl::CollisionObject<S> *s1, const fcl::CollisionObject<S> *s2,

nit: pointer next to type.


test/test_fcl_sphere_box.cpp, line 156 at r3 (raw file):

          const fcl::CollisionObject<S> *s1, const fcl::CollisionObject<S> *s2,
          S expected_depth, const Vector3<S> &expected_normal,
          const Vector3<S> &expected_pos, Real eps) {

nit: here and in other places. I tend to reserve "epsilon" for "machine epsilon". While I reserve the world "tolerance" for these test specific numbers to compare quantities.


test/test_fcl_sphere_box.cpp, line 166 at r3 (raw file):

          std::vector<fcl::Contact<S>> contacts;
          collision_result.getContacts(contacts);
          GTEST_ASSERT_EQ(static_cast<int>(contacts.size()), one_contact);

BTW what's the difference with ASSERT_EQ?


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

set(tests
        test_sphere_box.cpp

nit: is the indentation correct?

@SeanCurtis-TRI SeanCurtis-TRI force-pushed the PR_box_sphere_collision branch 2 times, most recently from 61d38bf to 48d5c20 Compare July 25, 2018 18:25
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.

-(Status: on hold) Ok, I've resolved the CI failure to the degree I will (and addressed comments so far). It's open season on this PR. Feel free to have at it.

Reviewable status: 6 of 14 files reviewed, 9 unresolved discussions (waiting on @amcastro-tri and @SeanCurtis-TRI)


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box-inl.h, line 61 at r2 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

Nit: frame B was not defined. Shortcut, “...its canonical frame B....”

Done


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box-inl.h, line 73 at r2 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

Nit: no GSG I pressume? And no intention on adopting it either right? I just thought the output in the header file were pointers and that probably u’d like to match that here?

Done
There is no GSG. And I remember wrestling with this; I think, ultimately, I wanted to avoid the whole "confirm the output parameter is not null" thing and streamline setting its values. And since I wasn't constrained by GSG, I thought, "what the hell?"

Ultimately, since we'd like to push this towards GSG, I should probably do it. SIiiigh.


test/eigen_matrix_compare.h, line 35 at r4 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

regarding the license, is it ok to copy it into a file grabbed from somewhere else? maybe question form @sherm1

nit: does the author tag applies given the disclaimer below?

I killed the author tag. The license is still copyrighted TRI and I don't think the BSD license is any looser than Drake's. So, we can defer this to people who are more license savvy than I. @sherm1? Thoughts?


test/test_fcl_collision.cpp, line 831 at r4 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

"Tests the tolerance value in the CollisionRequest, confirming that it propagates down to the solution. It creates a box and sphere and positions"

I see why you remove this test now (given sphere-box now is analytic). However, that the tolerance propagates down the pipeline is not tested anymore? maybe a TODO would suffice.

I considered that. I originally tinkered with the possibility of swapping primitives and rephrasing the test. Ultimately, I realized this is a ridiculously big test just to determine that a value gets set. As we touch the code and grow the unit tests, it'll get covered in a more coherent way. Also, I regret putting the test in in the first place (yes, it was me.)


test/test_fcl_sphere_box.cpp, line 78 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

δ / 2? is than an FCL convention? so contact point is always half way of the total penetration?

Yep. Although fcl isn't really good at conventions. We have been gradually scrubbing the code so that the interpretation of contact point is consistent and this value.


test/test_fcl_sphere_box.cpp, line 106 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

BTW std::make_shared()?

Done -- I mindlessly copied and pasted that pattern from elsewhere. Thanks for calling that out.


test/test_fcl_sphere_box.cpp, line 134 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

the docs on this parameter are pretty much lacking. Could you add here a one liner about what this parameter is for?

Done


test/test_fcl_sphere_box.cpp, line 135 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

BTW for my own education only, when would I want the paramter num_max_contacts to be different from one and what would it accomplish?

It depends. Some algorithms can provide more values (like the box box can provide several). I'm not sure how robust it is or how general it is. It's undocumented, so I'd have to go spelunking to fully understand the implications.


test/test_fcl_sphere_box.cpp, line 142 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

could you comment why:

  • half_size + r? would the test work if I use an x value of just half_size?
  • Why those values close to zero? (-eps, 0, eps). What's special about them?

Done


test/test_fcl_sphere_box.cpp, line 154 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

nit: pointer next to type.

Done


test/test_fcl_sphere_box.cpp, line 156 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

nit: here and in other places. I tend to reserve "epsilon" for "machine epsilon". While I reserve the world "tolerance" for these test specific numbers to compare quantities.

This should be a "btw" and not "nit". Calling it eps isn't actually a defect. Although you make a good point. Generally, I subscribe to the idea that epsilon is a concept -- some negligible amount that depends on the context. So, I'm going to leave it as is.


test/test_fcl_sphere_box.cpp, line 166 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

BTW what's the difference with ASSERT_EQ?

It's which version of GTEST you use; fcl doesn't have access to ASSERT_EQ.


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

Previously, amcastro-tri (Alejandro Castro) wrote…

nit: is the indentation correct?

No clue; but CLion keeps fighting me on this.


test/narrowphase/detail/primitive_shape_algorithm/test_sphere_box.cpp, line 261 at r2 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

It would probably be better if this test included a version nearest all six faces. This might pass because the underlying function mistakenly favors the +z direction and panders to this test.

Done

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.

Reviewable status: 6 of 14 files reviewed, 9 unresolved discussions (waiting on @amcastro-tri)


test/eigen_matrix_compare.h, line 35 at r4 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

I killed the author tag. The license is still copyrighted TRI and I don't think the BSD license is any looser than Drake's. So, we can defer this to people who are more license savvy than I. @sherm1? Thoughts?

FCL and Drake use the same license -- BSD 3-clause (Drake doesn't put a copy in every file, but FCL does so I think it is right to do that here.)

The copyright remains TRI, and Drake gets credit below, so I think this is all perfect.

@SeanCurtis-TRI SeanCurtis-TRI force-pushed the PR_box_sphere_collision branch from 48d5c20 to c7b7c60 Compare July 25, 2018 19:21
Copy link
Contributor

@amcastro-tri amcastro-tri left a comment

Choose a reason for hiding this comment

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

Great job @SeanCurtis-TRI! :lgtm_strong:
What are the policies regarding CI and platform review?

Reviewed 1 of 8 files at r3, 7 of 7 files at r5.
Reviewable status: all files reviewed, 3 unresolved discussions (waiting on @amcastro-tri and @SeanCurtis-TRI)


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h, line 78 at r2 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

Modified comment. PTAL

what about the size?
You say: "the contact point data will be appended to the end of this vector"

So, what is at the "front" of the vector? or is this vector always of size one?

Ah, wait, is that because contacts could have something on input and I'm just appending to it?


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h, line 100 at r5 (raw file):

 @tparam S The scalar parameter (must be a valid Eigen scalar).  */
template <typename S>
FCL_EXPORT bool sphereBoxIntersect(const Sphere<S>& sphere,

nit: should document the normal alwyas points out from the sphere into the box. Or is it a convention for all these sahpe1Shape2Intersect() methods?


test/test_fcl_sphere_box.cpp, line 166 at r3 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

It's which version of GTEST you use; fcl doesn't have access to ASSERT_EQ.

ah! that's why the main() at the bottom of the test files?


test/narrowphase/detail/primitive_shape_algorithm/test_sphere_box.cpp, line 179 at r5 (raw file):

  S expected_depth{-1};
  Vector3<S> expected_normal;
  Vector3<S> expected_pos;

nit: use monogram notation here as well for consistency? also easier for me to understand the EXPECTs 300 lines below.


test/narrowphase/detail/primitive_shape_algorithm/test_sphere_box.cpp, line 474 at r5 (raw file):

void EvalCollisionForTestConfiguration(const TestConfiguration<S>& config,
                                       const Transform3<S>& X_WB,
                                       const Matrix3<S>& R_SB,

btw: here and below. Interesting to see this non-symmetric signature. Why is it that you decided to pass the sphere's center through config rather than passing a X_SB as you do for the box?


test/narrowphase/detail/primitive_shape_algorithm/test_sphere_box.cpp, line 659 at r5 (raw file):

                                     EvalCollisionForTestConfiguration<float>);
  QueryWithVaryingWorldFrames<double>(GetUniformConfigurations<double>(),
      EvalCollisionForTestConfiguration<double>);

btw: indent.

@SeanCurtis-TRI SeanCurtis-TRI force-pushed the PR_box_sphere_collision branch from c7b7c60 to bd00ddd Compare July 25, 2018 23:28
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.

The CI failure has to be confirmed as a known CI failure with all appropriate lgtms, then it can be merged.

Reviewable status: 13 of 14 files reviewed, 3 unresolved discussions (waiting on @amcastro-tri and @SeanCurtis-TRI)


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h, line 78 at r2 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

what about the size?
You say: "the contact point data will be appended to the end of this vector"

So, what is at the "front" of the vector? or is this vector always of size one?

Ah, wait, is that because contacts could have something on input and I'm just appending to it?

Correct. I'd hoped that "append" would suggest that it'll be the last and whatever was there previously is still there.


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h, line 100 at r5 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

nit: should document the normal alwyas points out from the sphere into the box. Or is it a convention for all these sahpe1Shape2Intersect() methods?

Technically, the convention is that the normal points from o1 to o2 (see the docs for ContactPoint). IN this case, o1 "happens" to be a sphere. And it is a convention that makes it compatible with the macros defined in the two gjk_solvier_*-inl.h files.


test/test_fcl_sphere_box.cpp, line 166 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

ah! that's why the main() at the bottom of the test files?

That's actually something a bit different -- it's how they build.


test/narrowphase/detail/primitive_shape_algorithm/test_sphere_box.cpp, line 179 at r5 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

nit: use monogram notation here as well for consistency? also easier for me to understand the EXPECTs 300 lines below.

And yet, my actual tests look like:

EXPECT_EQ(pos, expected_pos) (in spirit, at least).

If I changed expected_pos to expected_pWC the test wouldn't read as clean.


test/narrowphase/detail/primitive_shape_algorithm/test_sphere_box.cpp, line 474 at r5 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

btw: here and below. Interesting to see this non-symmetric signature. Why is it that you decided to pass the sphere's center through config rather than passing a X_SB as you do for the box?

Because anything that is constant in test to test goes in the config and any parameter that varies from invocation to invocation comes from outside. (This was to facilitate tests that confirm that sphere orientation doesn't change the answer.)

Documentation updated.


test/narrowphase/detail/primitive_shape_algorithm/test_sphere_box.cpp, line 659 at r5 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

btw: indent.

Done

@SeanCurtis-TRI SeanCurtis-TRI force-pushed the PR_box_sphere_collision branch from bd00ddd to 368fc4d Compare July 26, 2018 14:02
Copy link
Contributor

@amcastro-tri amcastro-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 r6.
Reviewable status: :shipit: complete! all files reviewed, all discussions resolved

@SeanCurtis-TRI SeanCurtis-TRI force-pushed the PR_box_sphere_collision branch from 368fc4d to af88709 Compare July 30, 2018 15: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.

The code has been updated. When the sphere center got close to the box's surface, the normals/positions of the contact would go crazy because values would be dominated by floating-point noise. The most recent revision captures that noise in tests (with sphere centers on the surface of the box) and modifies the intersection test to capture an appropriate epsilon.

PTAL

Reviewable status: 11 of 14 files reviewed, all discussions resolved (waiting on @amcastro-tri)

Copy link
Contributor

@amcastro-tri amcastro-tri left a comment

Choose a reason for hiding this comment

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

:LGTM:. Lets merge and push any other improvements (like more unit tests) in a separate PR.

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


test/narrowphase/detail/primitive_shape_algorithm/test_sphere_box.cpp, line 312 at r7 (raw file):

  // Sub-case: Sphere center lies on face.
  {

would it be worth testing what happens when you are "epsilon" away from the face?, say 16*std::numeric_limists<S>::epsilon()?


test/narrowphase/detail/primitive_shape_algorithm/test_sphere_box.cpp, line 316 at r7 (raw file):

    configurations.emplace_back("Sphere center lies on +z face", half_size, r,
                                p_BS, collides);
    TestConfiguration<S> &config = configurations.back();

minor: & next to type. Here and below.


test/narrowphase/detail/primitive_shape_algorithm/test_sphere_box.cpp, line 330 at r7 (raw file):

    TestConfiguration<S> &config = configurations.back();
    config.expected_depth = r;
    config.expected_normal = -Vector3<S>::UnitX();

minor: maybe small local comment on why you expect this to be the selected normal?

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.

Reviewable status: all files reviewed, 2 unresolved discussions (waiting on @SeanCurtis-TRI)


test/narrowphase/detail/primitive_shape_algorithm/test_sphere_box.cpp, line 312 at r7 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

would it be worth testing what happens when you are "epsilon" away from the face?, say 16*std::numeric_limists<S>::epsilon()?

Added a todo.


test/narrowphase/detail/primitive_shape_algorithm/test_sphere_box.cpp, line 316 at r7 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

minor: & next to type. Here and below.

I've finally figure out what it is -- fcl doesn't have a .clang-format file that specifies where the & goes, so when I clang format a line like this, the & moves. I went ahead and corrected these.


test/narrowphase/detail/primitive_shape_algorithm/test_sphere_box.cpp, line 330 at r7 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

minor: maybe small local comment on why you expect this to be the selected normal?

Done

@SeanCurtis-TRI SeanCurtis-TRI force-pushed the PR_box_sphere_collision branch from af88709 to 902948b Compare July 31, 2018 15:30
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 Do you want to take a look at this? Otherwise, when it passes CI, I'm going to merge.

Reviewable status: 13 of 14 files reviewed, 2 unresolved discussions (waiting on @amcastro-tri)

@SeanCurtis-TRI SeanCurtis-TRI force-pushed the PR_box_sphere_collision branch from 902948b to 52dfbf3 Compare July 31, 2018 15:58
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.

I'll take a look while CI is running but if you don't hear from me, merge away!

Reviewable status: 13 of 15 files reviewed, 2 unresolved discussions (waiting on @amcastro-tri)

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.

Reviewable status: 13 of 15 files reviewed, 3 unresolved discussions (waiting on @amcastro-tri and @SeanCurtis-TRI)


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h, line 76 at r8 (raw file):

// the implementation in sphere-sphere contact.

// @{

BTW does this work properly with a space after //? Doxygen should parse that as an ordinary developer comment, I would think (though likely it special-cases this somehow).


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h, line 85 at r8 (raw file):

 characterization of collision in the provided vector.

 The reported depth is guaranteed to be continuous. The normal and

Nit: consider "continuous with respect to the relative pose of the two objects."

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.

Wow! Those tests are amazing. Awesome. :lgtm_strong:

Reviewed 1 of 1 files at r1, 3 of 11 files at r2, 2 of 8 files at r3, 5 of 7 files at r5, 2 of 3 files at r7, 2 of 2 files at r8.
Reviewable status: all files reviewed, 4 unresolved discussions (waiting on @amcastro-tri and @SeanCurtis-TRI)


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box-inl.h, line 35 at r8 (raw file):

 */

/** @author Sean Curtis <[email protected]> */

BTW consider appending a year (2018) as we do in Drake.


test/test_fcl_geometric_shapes.cpp, line 842 at r8 (raw file):

  const bool check_depth = true;
  const bool check_normal = true;
  const bool check_opposite_normal = false;

BTW consider constant naming convention like kCollides, kCheckPosition, etc. so these don't look like variables?


test/test_fcl_sphere_box.cpp, line 81 at r8 (raw file):

//  - Contact normal should be [0, 0, -1] (pointing from sphere into box).
//
// NOTE: Orientation on the sphere should *not* make a difference and is not

Nit: on -> of


test/narrowphase/detail/primitive_shape_algorithm/test_sphere_box.cpp, line 66 at r8 (raw file):

// evaluating: X_FB.inverse() * X_FS ends up doing the equivalent of multiplying
// two 4x4 matrices (rather than exploiting the compact affine representation).
// As such, it leaks a *bit* more error into the computation and this extra

FYI I read "bit" here after reading the previous comment and assumed you meant literally one bit of precision. Maybe say "small amount" or something like that to avoid the dual meanings of "bit" here?

By default, the GJK solver was being used for performing distance queries
between box's and spheres. For small features, the answer was being
dominated by the iterative tolerance and producing wildly problematic
values. The logical thing to do is to perform sphere-box collisions using
knowledge of the primitives.

This commit adds the following:
  - A new test illustrating the error of GJK is used
    (see test_fcl_sphere_box.cpp)
  - Borrows the CompareMatrices functionality from Drake and adds it to FCL.
  - Adds the custom sphere-box collision (sphere_box.h and sphere_box-inl.h)
  - Adds *extensive* unit tests on the custom algorithm.
  - Ties the custom algorithm into the libccd and indep GJK solvers.
  - Remove a useless conflicting test from test_fcl_collision (it's only
    useless in retrospect). And its formulation can't help but become
    corrupt.
  - Update *other* tests that otherwise depend on box-sphere collision.
@SeanCurtis-TRI SeanCurtis-TRI force-pushed the PR_box_sphere_collision branch from 52dfbf3 to f6ff3d0 Compare July 31, 2018 17:46
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.

Done

Reviewable status: 10 of 15 files reviewed, 2 unresolved discussions (waiting on @amcastro-tri and @sherm1)


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h, line 76 at r8 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW does this work properly with a space after //? Doxygen should parse that as an ordinary developer comment, I would think (though likely it special-cases this somehow).

Done Not sure. But now corrected.


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h, line 85 at r8 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

Nit: consider "continuous with respect to the relative pose of the two objects."

Done


include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box-inl.h, line 35 at r8 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW consider appending a year (2018) as we do in Drake.

Done


test/test_fcl_geometric_shapes.cpp, line 842 at r8 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW consider constant naming convention like kCollides, kCheckPosition, etc. so these don't look like variables?

Given the strong suggestion that variables with that name are of static storage duration, I'm going to leave them as is.


test/test_fcl_sphere_box.cpp, line 81 at r8 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

Nit: on -> of

Done


test/narrowphase/detail/primitive_shape_algorithm/test_sphere_box.cpp, line 66 at r8 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

FYI I read "bit" here after reading the previous comment and assumed you meant literally one bit of precision. Maybe say "small amount" or something like that to avoid the dual meanings of "bit" here?

Done

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 r9.
Reviewable status: all files reviewed, 1 unresolved discussion (waiting on @amcastro-tri)


test/test_fcl_geometric_shapes.cpp, line 842 at r8 (raw file):

Previously, SeanCurtis-TRI (Sean Curtis) wrote…

Given the strong suggestion that variables with that name are of static storage duration, I'm going to leave them as is.

To me the most important phrase there is "Variables ... whose value is fixed for the duration of the program" (and the convention is optional for automatic variables). I interpret that as "variables that could have had static storage duration". I like to use it for values that are fixed for the lifetime of the program, regardless of how they happen to be declared. For example, they are commonly used for enumerations, which actually don't have any storage.

But totally an author's preference item here!

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.

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


test/test_fcl_geometric_shapes.cpp, line 842 at r8 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

To me the most important phrase there is "Variables ... whose value is fixed for the duration of the program" (and the convention is optional for automatic variables). I interpret that as "variables that could have had static storage duration". I like to use it for values that are fixed for the lifetime of the program, regardless of how they happen to be declared. For example, they are commonly used for enumerations, which actually don't have any storage.

But totally an author's preference item here!

Yep. In this case, because it's optional, I like the readability of the underscore more than the camel case required if I clearly mark them as "constant". I guess, ideally, I'd use k_check_position which marks things as constant and gives visible word delineation. But that's not part of the style guide at all.

Also, in some vague back corner of the mind, I think that acknowledging static storage duration has value and applying the k prefix outside of that context dilutes that association. But please don't press me on what that value is -- I've not thought it all the way through.

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.

Dismissed @amcastro-tri from a discussion.
Reviewable status: :shipit: complete! all files reviewed, all discussions resolved

@SeanCurtis-TRI SeanCurtis-TRI merged commit 8fb2ce0 into flexible-collision-library:master Jul 31, 2018
@SeanCurtis-TRI
Copy link
Contributor Author

Merging with single, known CI error (test_fcl_box_box in mac release).

@SeanCurtis-TRI SeanCurtis-TRI deleted the PR_box_sphere_collision branch August 4, 2018 03:12
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