test_fcl_sphere_cylinder.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018. Toyota Research Institute
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of CNRS-LAAS and AIST nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
37 #include <memory>
38 
39 #include <gtest/gtest.h>
40 #include <Eigen/Dense>
41 
42 #include "eigen_matrix_compare.h"
45 
46 // TODO(SeanCurtis-TRI): Modify this test so it can be re-used for the distance
47 // query -- such that the sphere is slightly separated instead of slightly
48 // penetrating. See test_sphere_cylinder.cpp for an example.
49 
50 // This collides a cylinder with a sphere. The cylinder is disk-like with a
51 // large radius (r_c) and small height (h_c) and its geometric frame is aligned
52 // with the world frame. The sphere has radius r_s and is positioned at
53 // (sx, sy, sz) with an identity orientation. In this configuration, the sphere
54 // penetrates the cylinder slightly on the top face near the edge. The contact
55 // is *fully* contained in that face. (As illustrated below.)
56 //
57 // Side view
58 // z small sphere
59 // ┆ ↓
60 // ┏━━━━━━━━━━━━┿━━━━◯━━━━━━┓ ┬
61 // ┄┄┄┄┄┄╂┄┄┄┄┄┄┄┄┄┄┄┄┼┄┄┄┄┄┄┄┄┄┄┄╂┄ x h_c
62 // ┗━━━━━━━━━━━━┿━━━━━━━━━━━┛ ┴
63 // ┆
64 //
65 // ├──── r_c───┤
66 //
67 // Top view
68 // y
69 // ┆
70 // ******* small sphere ┬
71 // ** ┆ **╱ │
72 // * ┆ ◯ * │
73 // * ┆ * │
74 // * ┆ * r_c
75 // * ┆ * │
76 // * ┆ * │
77 // * ┆ * │
78 // ┄┄┄┄┄┄┄*┄┄┄┄┄┄┄┄┄┄┼┄┄┄┄┄┄┄┄┄┄*┄┄┄┄ x ┴
79 // * ┆ *
80 // * ┆ *
81 // * ┆ *
82 // * ┆ *
83 // * ┆ *
84 // * ┆ *
85 // ** ┆ **
86 // *******
87 // ┆
88 // Properties of expected outcome:
89 // - One contact *should* be reported,
90 // - Penetration depth δ should be: r_s - (sz - h_c / 2),
91 // - Contact point should be at: [sx, sy, h_c / 2 - δ / 2], and
92 // - Contact normal should be [0, 0, -1] (pointing from sphere into cylinder).
93 //
94 // NOTE: Orientation of the sphere should *not* make a difference and is not
95 // tested here; it relies on the sphere-cylinder primitive algorithm unit tests
96 // to have robustly tested that.
97 //
98 // This test *fails* if GJK is used to evaluate the collision. It passes if the
99 // custom sphere-cylinder algorithm is used, and, therefore, its purpose is to
100 // confirm that the custom algorithm is being applied. It doesn't exhaustively
101 // test sphere-cylinder collision. It merely confirms the tested primitive
102 // algorithm has been wired up correctly.
103 template <typename S>
105  using fcl::Vector3;
106  using Real = typename fcl::constants<S>::Real;
107  const Real eps = fcl::constants<S>::eps();
108 
109  // Configure geometry.
110 
111  // Cylinder and sphere dimensions.
112  const Real r_c = 9;
113  const Real h_c = 0.0025;
114  const Real r_s = 0.0015;
115 
116  auto sphere_geometry = std::make_shared<fcl::Sphere<S>>(r_s);
117  auto cylinder_geometry = std::make_shared<fcl::Cylinder<S>>(r_c, h_c);
118 
119  // Pose of the cylinder in the world frame.
121 
122  // Compute multiple sphere locations. All at the same height to produce a
123  // fixed, expected penetration depth of half of its radius. The reported
124  // position of the contact will have the x- and y- values of the sphere
125  // center, but be half the target_depth below the +z face, i.e.,
126  // pz = (h_c / 2) - (target_depth / 2)
127  const Real target_depth = r_s * 0.5;
128  // Sphere center's height (position in z).
129  const Real sz = h_c / 2 + r_s - target_depth;
130  const Real pz = h_c / 2 - target_depth / 2;
131  // This transform will get repeatedly modified in the nested for loop below.
133 
134  fcl::CollisionObject<S> sphere(sphere_geometry, X_WS);
135  fcl::CollisionObject<S> cylinder(cylinder_geometry, X_WC);
136 
137  // Expected results. (Expected position is defined inside the for loop as it
138  // changes with each new position of the sphere.)
139  const S expected_depth = target_depth;
140  // This normal direction assumes the *sphere* is the first collision object.
141  // If the order is reversed, the normal must be likewise reversed.
142  const Vector3<S> expected_normal = -Vector3<S>::UnitZ();
143 
144  // Set up the collision request.
145  fcl::CollisionRequest<S> collision_request(1 /* num contacts */,
146  true /* enable_contact */);
147  collision_request.gjk_solver_type = solver_type;
148 
149  // Sample around the surface of the +z face on the disk for a fixed
150  // penetration depth. Note: the +z face is a disk with radius r_c. Notes on
151  // the selected samples:
152  // - We've picked positions such that the *whole* sphere projects onto the
153  // +z face. This *guarantees* that the contact is completely contained in
154  // the +z face so there is no possible ambiguity in the results.
155  // - We've picked points out near the boundaries, in the middle, and *near*
156  // zero without being zero. The GJK algorithm can actually provide the
157  // correct result at the (eps, eps) sample points. We leave those sample
158  // points in to confirm no degradation.
159  const std::vector<Real> r_values{0, eps, r_c / 2, r_c - r_s};
160  const S pi = fcl::constants<S>::pi();
161  const std::vector<Real> theta_values{0, pi/2, pi, 3 * pi / 4};
162 
163  for (const Real r : r_values) {
164  for (const Real theta : theta_values ) {
165  // Don't just evaluate at nice, axis-aligned directions. Pick some number
166  // that can't be perfectly represented.
167  const Real angle = theta + pi / 7;
168  const Real sx = cos(angle) * r;
169  const Real sy = sin(angle) * r;
170  // Repose the sphere.
171  X_WS.translation() << sx, sy, sz;
172  sphere.setTransform(X_WS);
173 
174  auto evaluate_collision = [&collision_request, &X_WS](
176  S expected_depth, const Vector3<S>& expected_normal,
177  const Vector3<S>& expected_pos, Real eps) {
178  // Compute collision.
179  fcl::CollisionResult<S> collision_result;
180  std::size_t contact_count =
181  fcl::collide(s1, s2, collision_request, collision_result);
182 
183  // Test answers
184  if (contact_count == collision_request.num_max_contacts) {
185  std::vector<fcl::Contact<S>> contacts;
186  collision_result.getContacts(contacts);
187  GTEST_ASSERT_EQ(contacts.size(), collision_request.num_max_contacts);
188 
189  const fcl::Contact<S>& contact = contacts[0];
191  << "Sphere at: " << X_WS.translation().transpose();
194  eps,
196  << "Sphere at: " << X_WS.translation().transpose();
199  << "Sphere at: " << X_WS.translation().transpose();
200  } else {
201  EXPECT_TRUE(false) << "No contacts reported for sphere at: "
202  << X_WS.translation().transpose();
203  }
204  };
205 
206  Vector3<S> expected_pos{sx, sy, pz};
207  evaluate_collision(&sphere, &cylinder, expected_depth, expected_normal,
208  expected_pos, eps);
209  evaluate_collision(&cylinder, &sphere, expected_depth, -expected_normal,
210  expected_pos, eps);
211  }
212  }
213 }
214 
215 GTEST_TEST(FCL_SPHERE_CYLINDER, LargCylinderSmallSphere_ccd) {
216  LargeCylinderSmallSphereTest<double>(fcl::GJKSolverType::GST_LIBCCD);
217  LargeCylinderSmallSphereTest<float>(fcl::GJKSolverType::GST_LIBCCD);
218 }
219 
220 GTEST_TEST(FCL_SPHERE_CYLINDER, LargBoxSmallSphere_indep) {
221  LargeCylinderSmallSphereTest<double>(fcl::GJKSolverType::GST_INDEP);
222  LargeCylinderSmallSphereTest<float>(fcl::GJKSolverType::GST_INDEP);
223 }
224 
225 //==============================================================================
226 int main(int argc, char* argv[]) {
227  ::testing::InitGoogleTest(&argc, argv);
228  return RUN_ALL_TESTS();
229 }
fcl::CollisionObject::setTransform
void setTransform(const Matrix3< S > &R, const Vector3< S > &T)
set object's transform
Definition: collision_object-inl.h:198
fcl::Transform3
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
fcl::CollisionRequest::gjk_solver_type
GJKSolverType gjk_solver_type
Enumeration indicating the GJK solver implementation to use.
Definition: collision_request.h:78
fcl::GJKSolverType
GJKSolverType
Type of narrow phase GJK solver.
Definition: gjk_solver_type.h:45
collision_object.h
fcl::CollisionRequest::num_max_contacts
size_t num_max_contacts
The maximum number of contacts that can be returned.
Definition: collision_request.h:59
eigen_matrix_compare.h
fcl::CompareMatrices
::testing::AssertionResult CompareMatrices(const Eigen::MatrixBase< DerivedA > &m1, const Eigen::MatrixBase< DerivedB > &m2, double tolerance=0.0, MatrixCompareType compare_type=MatrixCompareType::absolute)
Definition: eigen_matrix_compare.h:63
r_s
S r_s
Definition: test_sphere_cylinder.cpp:187
fcl::constants::eps
static constexpr Real eps()
Returns ε for the precision of the underlying scalar type.
Definition: constants.h:151
fcl::Contact
Contact information returned by collision.
Definition: contact.h:48
fcl::Contact::normal
Vector3< S > normal
contact normal, pointing from o1 to o2
Definition: contact.h:71
LargeCylinderSmallSphereTest
void LargeCylinderSmallSphereTest(fcl::GJKSolverType solver_type)
Definition: test_fcl_sphere_cylinder.cpp:104
expected_pos
Vector3< S > expected_pos
Definition: test_sphere_box.cpp:181
fcl::CollisionResult
collision result
Definition: collision_request.h:48
EXPECT_TRUE
#define EXPECT_TRUE(args)
fcl::Vector3
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
GTEST_TEST
GTEST_TEST(FCL_SPHERE_CYLINDER, LargCylinderSmallSphere_ccd)
Definition: test_fcl_sphere_cylinder.cpp:215
distance.h
fcl::constants::Real
detail::ScalarTrait< S >::type Real
Definition: constants.h:131
EXPECT_NEAR
#define EXPECT_NEAR(a, b, prec)
fcl::GST_LIBCCD
@ GST_LIBCCD
Definition: gjk_solver_type.h:45
fcl::Contact::pos
Vector3< S > pos
contact position, in world space
Definition: contact.h:74
fcl::MatrixCompareType::absolute
@ absolute
fcl::CollisionRequest
Parameters for performing collision request.
Definition: collision_request.h:52
expected_depth
S expected_depth
Definition: test_half_space_convex.cpp:152
fcl::collide
template FCL_EXPORT std::size_t collide(const CollisionObject< double > *o1, const CollisionObject< double > *o2, const CollisionRequest< double > &request, CollisionResult< double > &result)
r
S r
Definition: test_sphere_box.cpp:171
main
int main(int argc, char *argv[])
Definition: test_fcl_sphere_cylinder.cpp:226
expected_normal
Vector3< S > expected_normal
Definition: test_sphere_box.cpp:180
fcl::CollisionResult::getContacts
void getContacts(std::vector< Contact< S >> &contacts_)
get all the contacts
Definition: collision_result-inl.h:107
fcl::Contact::penetration_depth
S penetration_depth
penetration depth
Definition: contact.h:77
fcl::constants::pi
static constexpr S pi()
The mathematical constant pi.
Definition: constants.h:134
r_c
S r_c
Definition: test_sphere_cylinder.cpp:185
fcl::GST_INDEP
@ GST_INDEP
Definition: gjk_solver_type.h:45
fcl::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: collision_object.h:51


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:49