security_margin.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2022, INRIA.
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 Willow Garage, Inc. 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 
35 #define BOOST_TEST_MODULE FCL_SECURITY_MARGIN
36 #include <boost/test/included/unit_test.hpp>
37 
38 #include <cmath>
39 #include <iostream>
40 #include <hpp/fcl/distance.h>
41 #include <hpp/fcl/math/transform.h>
42 #include <hpp/fcl/collision.h>
47 
48 #include "utility.h"
49 
50 using namespace hpp::fcl;
58 using hpp::fcl::Vec3f;
59 
60 #define MATH_SQUARED(x) (x * x)
61 
63  CollisionGeometryPtr_t b1(new hpp::fcl::Box(1, 1, 1));
64  CollisionGeometryPtr_t b2(new hpp::fcl::Box(1, 1, 1));
65 
66  const Transform3f tf1;
67  const Transform3f tf2_collision(Vec3f(0, 1, 1));
68  hpp::fcl::Box s1(1, 1, 1);
69  hpp::fcl::Box s2(1, 1, 1);
70  const double tol = 1e-8;
71 
72  AABB bv1, bv2;
73  computeBV(s1, Transform3f(), bv1);
74  computeBV(s2, Transform3f(), bv2);
75 
76  // No security margin - collision
77  {
78  CollisionRequest collisionRequest(CONTACT, 1);
79  AABB bv2_transformed;
80  computeBV(s2, tf2_collision, bv2_transformed);
81  FCL_REAL sqrDistLowerBound;
82  bool res =
83  bv1.overlap(bv2_transformed, collisionRequest, sqrDistLowerBound);
84  BOOST_CHECK(res);
85  BOOST_CHECK_CLOSE(sqrDistLowerBound, 0, tol);
86  }
87 
88  // No security margin - no collision
89  {
90  CollisionRequest collisionRequest(CONTACT, 1);
91  const double distance = 0.01;
92  Transform3f tf2_no_collision(
93  Vec3f(tf2_collision.getTranslation() + Vec3f(0, 0, distance)));
94  AABB bv2_transformed;
95  computeBV(s2, tf2_no_collision, bv2_transformed);
96  FCL_REAL sqrDistLowerBound;
97  bool res =
98  bv1.overlap(bv2_transformed, collisionRequest, sqrDistLowerBound);
99  BOOST_CHECK(!res);
100  BOOST_CHECK_CLOSE(sqrDistLowerBound, MATH_SQUARED(distance), tol);
101  }
102 
103  // Security margin - collision
104  {
105  CollisionRequest collisionRequest(CONTACT, 1);
106  const double distance = 0.01;
107  collisionRequest.security_margin = distance;
108  Transform3f tf2_no_collision(
109  Vec3f(tf2_collision.getTranslation() + Vec3f(0, 0, distance)));
110  AABB bv2_transformed;
111  computeBV(s2, tf2_no_collision, bv2_transformed);
112  FCL_REAL sqrDistLowerBound;
113  bool res =
114  bv1.overlap(bv2_transformed, collisionRequest, sqrDistLowerBound);
115  BOOST_CHECK(res);
116  BOOST_CHECK_SMALL(sqrDistLowerBound, tol);
117  }
118 
119  // Negative security margin - collion because the two boxes are in contact
120  {
121  CollisionRequest collisionRequest(CONTACT, 1);
122  const double distance = -0.01;
123  collisionRequest.security_margin = distance;
124  const Transform3f tf2(
125  Vec3f(tf2_collision.getTranslation() + Vec3f(0, distance, distance)));
126  AABB bv2_transformed;
127  computeBV(s2, tf2, bv2_transformed);
128  FCL_REAL sqrDistLowerBound;
129  bool res =
130  bv1.overlap(bv2_transformed, collisionRequest, sqrDistLowerBound);
131  BOOST_CHECK(res);
132  BOOST_CHECK_SMALL(sqrDistLowerBound, tol);
133  }
134 
135  // Negative security margin - no collision
136  {
137  CollisionRequest collisionRequest(CONTACT, 1);
138  const double distance = -0.01;
139  collisionRequest.security_margin = distance;
140  AABB bv2_transformed;
141  computeBV(s2, tf2_collision, bv2_transformed);
142  FCL_REAL sqrDistLowerBound;
143  bool res =
144  bv1.overlap(bv2_transformed, collisionRequest, sqrDistLowerBound);
145  BOOST_CHECK(!res);
146  BOOST_CHECK_CLOSE(
147  sqrDistLowerBound,
148  MATH_SQUARED((std::sqrt(2) * collisionRequest.security_margin)), tol);
149  }
150 }
151 
152 BOOST_AUTO_TEST_CASE(aabb_aabb_degenerated_cases) {
153  CollisionGeometryPtr_t b1(new hpp::fcl::Box(1, 1, 1));
154  CollisionGeometryPtr_t b2(new hpp::fcl::Box(1, 1, 1));
155 
156  const Transform3f tf1;
157  const Transform3f tf2_collision(Vec3f(0, 0, 0));
158  hpp::fcl::Box s1(1, 1, 1);
159  hpp::fcl::Box s2(1, 1, 1);
160 
161  AABB bv1, bv2;
162  computeBV(s1, Transform3f(), bv1);
163  computeBV(s2, Transform3f(), bv2);
164 
165  // The two AABB are collocated
166  {
167  CollisionRequest collisionRequest(CONTACT, 1);
168  const double distance = -2.;
169  collisionRequest.security_margin = distance;
170  AABB bv2_transformed;
171  computeBV(s2, tf2_collision, bv2_transformed);
172  FCL_REAL sqrDistLowerBound;
173  bool res =
174  bv1.overlap(bv2_transformed, collisionRequest, sqrDistLowerBound);
175  BOOST_CHECK(!res);
176  }
177 
178  const AABB bv3;
179  BOOST_CHECK(!bv1.overlap(bv3));
180 }
181 
182 BOOST_AUTO_TEST_CASE(sphere_sphere) {
185 
186  const Transform3f tf1;
187  const Transform3f tf2_collision(Vec3f(0, 0, 3));
188 
189  // No security margin - collision
190  {
191  CollisionRequest collisionRequest(CONTACT, 1);
192  CollisionResult collisionResult;
193  collide(s1.get(), tf1, s2.get(), tf2_collision, collisionRequest,
194  collisionResult);
195  BOOST_CHECK(collisionResult.isCollision());
196  BOOST_CHECK_CLOSE(collisionResult.distance_lower_bound, 0, 1e-8);
197  BOOST_CHECK_SMALL(-collisionResult.getContact(0).penetration_depth, 1e-8);
198  }
199 
200  // No security margin - no collision
201  {
202  CollisionRequest collisionRequest(CONTACT, 1);
203  CollisionResult collisionResult;
204  const double distance = 0.01;
205  Transform3f tf2_no_collision(
206  Vec3f(tf2_collision.getTranslation() + Vec3f(0, 0, distance)));
207  collide(s1.get(), tf1, s2.get(), tf2_no_collision, collisionRequest,
208  collisionResult);
209  BOOST_CHECK(!collisionResult.isCollision());
210  BOOST_CHECK_CLOSE(collisionResult.distance_lower_bound, distance, 1e-8);
211  }
212 
213  // Positive security margin - collision
214  {
215  CollisionRequest collisionRequest(CONTACT, 1);
216  CollisionResult collisionResult;
217  const double distance = 0.01;
218  collisionRequest.security_margin = distance;
219  Transform3f tf2_no_collision(
220  Vec3f(tf2_collision.getTranslation() + Vec3f(0, 0, distance)));
221  collide(s1.get(), tf1, s2.get(), tf2_no_collision, collisionRequest,
222  collisionResult);
223  BOOST_CHECK(collisionResult.isCollision());
224  BOOST_CHECK_CLOSE(collisionResult.distance_lower_bound, 0, 1e-8);
225  BOOST_CHECK_CLOSE(-collisionResult.getContact(0).penetration_depth,
226  distance, 1e-8);
227  }
228 
229  // Negative security margin - collion because the two spheres are in contact
230  {
231  CollisionRequest collisionRequest(CONTACT, 1);
232  CollisionResult collisionResult;
233  const double distance = -0.01;
234  collisionRequest.security_margin = distance;
236  Vec3f(tf2_collision.getTranslation() + Vec3f(0, 0, distance)));
237  collide(s1.get(), tf1, s2.get(), tf2, collisionRequest, collisionResult);
238  BOOST_CHECK(collisionResult.isCollision());
239  BOOST_CHECK_SMALL(collisionResult.distance_lower_bound, 1e-8);
240  BOOST_CHECK_CLOSE(-collisionResult.getContact(0).penetration_depth,
241  distance, 1e-8);
242  }
243 
244  // Negative security margin - no collision
245  {
246  CollisionRequest collisionRequest(CONTACT, 1);
247  CollisionResult collisionResult;
248  collisionRequest.security_margin = -0.01;
249  collide(s1.get(), tf1, s2.get(), tf2_collision, collisionRequest,
250  collisionResult);
251  BOOST_CHECK(!collisionResult.isCollision());
252  BOOST_CHECK_CLOSE(collisionResult.distance_lower_bound,
253  -collisionRequest.security_margin, 1e-8);
254  }
255 }
256 
257 BOOST_AUTO_TEST_CASE(capsule_capsule) {
258  CollisionGeometryPtr_t c1(new hpp::fcl::Capsule(0.5, 1.));
260 
261  const Transform3f tf1;
262  const Transform3f tf2_collision(Vec3f(0, 1., 0));
263 
264  // No security margin - collision
265  {
266  CollisionRequest collisionRequest(CONTACT, 1);
267  CollisionResult collisionResult;
268  collide(c1.get(), tf1, c2.get(), tf2_collision, collisionRequest,
269  collisionResult);
270  BOOST_CHECK(collisionResult.isCollision());
271  BOOST_CHECK_SMALL(collisionResult.distance_lower_bound, 1e-8);
272  BOOST_CHECK_SMALL(-collisionResult.getContact(0).penetration_depth, 1e-8);
273  }
274 
275  // No security margin - no collision
276  {
277  CollisionRequest collisionRequest(CONTACT, 1);
278  CollisionResult collisionResult;
279  const double distance = 0.01;
280  Transform3f tf2_no_collision(
281  Vec3f(tf2_collision.getTranslation() + Vec3f(0, distance, 0)));
282  collide(c1.get(), tf1, c2.get(), tf2_no_collision, collisionRequest,
283  collisionResult);
284  BOOST_CHECK(!collisionResult.isCollision());
285  BOOST_CHECK_CLOSE(collisionResult.distance_lower_bound, distance, 1e-8);
286  }
287 
288  // Positive security margin - collision
289  {
290  CollisionRequest collisionRequest(CONTACT, 1);
291  CollisionResult collisionResult;
292  const double distance = 0.01;
293  collisionRequest.security_margin = distance;
294  Transform3f tf2_no_collision(
295  Vec3f(tf2_collision.getTranslation() + Vec3f(0, distance, 0)));
296  collide(c1.get(), tf1, c2.get(), tf2_no_collision, collisionRequest,
297  collisionResult);
298  BOOST_CHECK(collisionResult.isCollision());
299  BOOST_CHECK_SMALL(collisionResult.distance_lower_bound, 1e-8);
300  BOOST_CHECK_CLOSE(-collisionResult.getContact(0).penetration_depth,
301  distance, 1e-8);
302  }
303 
304  // Negative security margin - collion because the two capsules are in contact
305  {
306  CollisionRequest collisionRequest(CONTACT, 1);
307  CollisionResult collisionResult;
308  const double distance = -0.01;
309  collisionRequest.security_margin = distance;
311  Vec3f(tf2_collision.getTranslation() + Vec3f(0, distance, 0)));
312  collide(c1.get(), tf1, c2.get(), tf2, collisionRequest, collisionResult);
313  BOOST_CHECK(collisionResult.isCollision());
314  BOOST_CHECK_SMALL(collisionResult.distance_lower_bound, 1e-8);
315  BOOST_CHECK_CLOSE(-collisionResult.getContact(0).penetration_depth,
316  distance, 1e-8);
317  }
318 
319  // Negative security margin - no collision
320  {
321  CollisionRequest collisionRequest(CONTACT, 1);
322  CollisionResult collisionResult;
323  collisionRequest.security_margin = -0.01;
324  collide(c1.get(), tf1, c2.get(), tf2_collision, collisionRequest,
325  collisionResult);
326  BOOST_CHECK(!collisionResult.isCollision());
327  BOOST_CHECK_CLOSE(collisionResult.distance_lower_bound, 0.01, 1e-8);
328  }
329 }
330 
332  CollisionGeometryPtr_t b1(new hpp::fcl::Box(1, 1, 1));
333  CollisionGeometryPtr_t b2(new hpp::fcl::Box(1, 1, 1));
334 
335  const Transform3f tf1;
336  const Transform3f tf2_collision(Vec3f(0, 1, 1));
337 
338  const double tol = 1e-3;
339 
340  // No security margin - collision
341  {
342  CollisionRequest collisionRequest(CONTACT, 1);
343  CollisionResult collisionResult;
344  collide(b1.get(), tf1, b2.get(), tf2_collision, collisionRequest,
345  collisionResult);
346  BOOST_CHECK(collisionResult.isCollision());
347  BOOST_CHECK_SMALL(collisionResult.distance_lower_bound, tol);
348  BOOST_CHECK_SMALL(-collisionResult.getContact(0).penetration_depth, 1e-8);
349  }
350 
351  // No security margin - no collision
352  {
353  CollisionRequest collisionRequest(CONTACT, 1);
354  const double distance = 0.01;
355  const Transform3f tf2_no_collision(
356  (tf2_collision.getTranslation() + Vec3f(0, 0, distance)).eval());
357 
358  CollisionResult collisionResult;
359  collide(b1.get(), tf1, b2.get(), tf2_no_collision, collisionRequest,
360  collisionResult);
361  BOOST_CHECK(!collisionResult.isCollision());
362  BOOST_CHECK_CLOSE(collisionResult.distance_lower_bound, distance, tol);
363  }
364 
365  // Positive security margin - collision
366  {
367  CollisionRequest collisionRequest(CONTACT, 1);
368  const double distance = 0.01;
369  collisionRequest.security_margin = distance;
370  CollisionResult collisionResult;
371  collide(b1.get(), tf1, b2.get(), tf2_collision, collisionRequest,
372  collisionResult);
373  BOOST_CHECK(collisionResult.isCollision());
374  BOOST_CHECK_CLOSE(collisionResult.distance_lower_bound,
375  -collisionRequest.security_margin, tol);
376  BOOST_CHECK_SMALL(-collisionResult.getContact(0).penetration_depth, 1e-8);
377  }
378 
379  // Negative security margin - no collision
380  {
381  CollisionRequest collisionRequest(CONTACT, 1);
382  collisionRequest.security_margin = -0.01;
383  CollisionResult collisionResult;
384  collide(b1.get(), tf1, b2.get(), tf2_collision, collisionRequest,
385  collisionResult);
386  BOOST_CHECK(!collisionResult.isCollision());
387  BOOST_CHECK_CLOSE(collisionResult.distance_lower_bound,
388  -collisionRequest.security_margin, tol);
389  }
390 
391  // Negative security margin - collision
392  {
393  CollisionRequest collisionRequest(CONTACT, 1);
394  const FCL_REAL distance = -0.01;
395  collisionRequest.security_margin = distance;
396  CollisionResult collisionResult;
397 
398  const Transform3f tf2((tf2_collision.getTranslation() +
399  Vec3f(0, collisionRequest.security_margin,
400  collisionRequest.security_margin))
401  .eval());
402  collide(b1.get(), tf1, b2.get(), tf2, collisionRequest, collisionResult);
403  BOOST_CHECK(collisionResult.isCollision());
404  BOOST_CHECK_SMALL(collisionResult.distance_lower_bound, tol);
405  BOOST_CHECK_CLOSE(-collisionResult.getContact(0).penetration_depth,
406  distance, tol);
407  }
408 }
409 
410 template <typename ShapeType1, typename ShapeType2>
411 void test_shape_shape(const ShapeType1& shape1, const Transform3f& tf1,
412  const ShapeType2& shape2,
413  const Transform3f& tf2_collision, const FCL_REAL tol) {
414  // No security margin - collision
415  {
416  CollisionRequest collisionRequest(CONTACT, 1);
417  CollisionResult collisionResult;
418  collide(&shape1, tf1, &shape2, tf2_collision, collisionRequest,
419  collisionResult);
420  BOOST_CHECK(collisionResult.isCollision());
421  BOOST_CHECK_SMALL(collisionResult.distance_lower_bound, tol);
422  BOOST_CHECK_SMALL(-collisionResult.getContact(0).penetration_depth, 1e-8);
423  }
424 
425  // No security margin - no collision
426  {
427  CollisionRequest collisionRequest(CONTACT, 1);
428  const double distance = 0.01;
429  const Transform3f tf2_no_collision(
430  (tf2_collision.getTranslation() + Vec3f(0, 0, distance)).eval());
431 
432  CollisionResult collisionResult;
433  collide(&shape1, tf1, &shape2, tf2_no_collision, collisionRequest,
434  collisionResult);
435  BOOST_CHECK(!collisionResult.isCollision());
436  BOOST_CHECK_CLOSE(collisionResult.distance_lower_bound, distance, tol);
437  }
438 
439  // Positive security margin - collision
440  {
441  CollisionRequest collisionRequest(CONTACT, 1);
442  const double distance = 0.01;
443  collisionRequest.security_margin = distance;
444  CollisionResult collisionResult;
445  collide(&shape1, tf1, &shape2, tf2_collision, collisionRequest,
446  collisionResult);
447  BOOST_CHECK(collisionResult.isCollision());
448  BOOST_CHECK_CLOSE(collisionResult.distance_lower_bound,
449  -collisionRequest.security_margin, tol);
450  BOOST_CHECK_SMALL(-collisionResult.getContact(0).penetration_depth, 1e-8);
451  }
452 
453  // Negative security margin - no collision
454  {
455  CollisionRequest collisionRequest(CONTACT, 1);
456  collisionRequest.security_margin = -0.01;
457  CollisionResult collisionResult;
458  collide(&shape1, tf1, &shape2, tf2_collision, collisionRequest,
459  collisionResult);
460  BOOST_CHECK(!collisionResult.isCollision());
461  BOOST_CHECK_CLOSE(
462  collisionResult.distance_lower_bound,
463  (collisionRequest.security_margin * tf2_collision.getTranslation())
464  .norm(),
465  tol);
466  }
467 
468  // Negative security margin - collision
469  {
470  CollisionRequest collisionRequest(CONTACT, 1);
471  const FCL_REAL distance = -0.01;
472  collisionRequest.security_margin = distance;
473  CollisionResult collisionResult;
474 
475  const Transform3f tf2((tf2_collision.getTranslation() +
476  Vec3f(0, collisionRequest.security_margin,
477  collisionRequest.security_margin))
478  .eval());
479  collide(&shape1, tf1, &shape2, tf2, collisionRequest, collisionResult);
480  BOOST_CHECK(collisionResult.isCollision());
481  BOOST_CHECK_SMALL(collisionResult.distance_lower_bound, tol);
482  BOOST_CHECK_CLOSE(-collisionResult.getContact(0).penetration_depth,
483  distance, tol);
484  }
485 }
486 
487 BOOST_AUTO_TEST_CASE(sphere_box) {
488  Box* box_ptr = new hpp::fcl::Box(1, 1, 1);
489  CollisionGeometryPtr_t b1(box_ptr);
490  BVHModel<OBBRSS> box_bvh_model = BVHModel<OBBRSS>();
491  generateBVHModel(box_bvh_model, *box_ptr, Transform3f());
492  box_bvh_model.buildConvexRepresentation(false);
493  ConvexBase& box_convex = *box_bvh_model.convex.get();
495 
496  const Transform3f tf1;
497  const Transform3f tf2_collision(Vec3f(0, 0, 1));
498 
499  const double tol = 1e-6;
500 
501  test_shape_shape(*b1.get(), tf1, *s2.get(), tf2_collision, tol);
502  test_shape_shape(box_convex, tf1, *s2.get(), tf2_collision, tol);
503 }
hpp::fcl::Vec3f
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
hpp::fcl::AABB::overlap
bool overlap(const AABB &other) const
Check whether two AABB are overlap.
Definition: BV/AABB.h:110
collision_object.h
test_shape_shape
void test_shape_shape(const ShapeType1 &shape1, const Transform3f &tf1, const ShapeType2 &shape2, const Transform3f &tf2_collision, const FCL_REAL tol)
Definition: security_margin.cpp:411
hpp::fcl::BVHModelBase::convex
shared_ptr< ConvexBase > convex
Convex<Triangle> representation of this object.
Definition: BVH/BVH_model.h:84
gjk.tf1
tuple tf1
Definition: test/scripts/gjk.py:27
hpp::fcl::Sphere
Center at zero point sphere.
Definition: shape/geometric_shapes.h:196
hpp::fcl::CONTACT
@ CONTACT
Definition: collision_data.h:229
hpp::fcl::CollisionResult::getContact
const Contact & getContact(size_t i) const
get the i-th contact calculated
Definition: collision_data.h:345
utility.h
hpp::fcl::computeBV
void computeBV(const S &s, const Transform3f &tf, BV &bv)
calculate a bounding volume for a shape in a specific configuration
Definition: geometric_shapes_utility.h:74
hpp::fcl::distance
HPP_FCL_DLLAPI FCL_REAL distance(const Matrix3f &R0, const Vec3f &T0, const kIOS &b1, const kIOS &b2, Vec3f *P=NULL, Vec3f *Q=NULL)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS.cpp:181
hpp::fcl::CollisionGeometryPtr_t
shared_ptr< CollisionGeometry > CollisionGeometryPtr_t
Definition: include/hpp/fcl/fwd.hh:96
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(aabb_aabb)
Definition: security_margin.cpp:62
geometric_shapes_utility.h
hpp::fcl::BVHModelBase::buildConvexRepresentation
void buildConvexRepresentation(bool share_memory)
Build this Convex<Triangle> representation of this model. The result is stored in attribute convex.
Definition: BVH_model.cpp:116
hpp::fcl::collide
HPP_FCL_DLLAPI std::size_t collide(const CollisionObject *o1, const CollisionObject *o2, const CollisionRequest &request, CollisionResult &result)
Main collision interface: given two collision objects, and the requirements for contacts,...
Definition: src/collision.cpp:63
res
res
distance.h
hpp::fcl::FCL_REAL
double FCL_REAL
Definition: data_types.h:65
hpp::fcl::CollisionRequest::security_margin
FCL_REAL security_margin
Distance below which objects are considered in collision. See Collision.
Definition: collision_data.h:251
MATH_SQUARED
#define MATH_SQUARED(x)
Definition: security_margin.cpp:60
hpp::fcl::CollisionRequest
request to the collision algorithm
Definition: collision_data.h:235
hpp::fcl::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: collision_object.h:215
gjk.tf2
tuple tf2
Definition: test/scripts/gjk.py:36
hpp::fcl::CollisionResult
collision result
Definition: collision_data.h:302
hpp::fcl::CollisionResult::isCollision
bool isCollision() const
return binary collision result
Definition: collision_data.h:339
hpp::fcl::Capsule
Capsule It is where is the distance between the point x and the capsule segment AB,...
Definition: shape/geometric_shapes.h:333
hpp::fcl::AABB
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Definition: BV/AABB.h:54
hpp::fcl
Definition: broadphase_bruteforce.h:45
hpp::fcl::Transform3f::getTranslation
const Vec3f & getTranslation() const
get translation
Definition: transform.h:100
hpp::fcl::Transform3f
Simple transform class used locally by InterpMotion.
Definition: transform.h:54
hpp::fcl::ConvexBase
Base for convex polytope.
Definition: shape/geometric_shapes.h:581
hpp::fcl::BVHModel
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: BVH/BVH_model.h:273
hpp::fcl::DistanceRequest
request to the distance computation
Definition: collision_data.h:392
hpp::fcl::DistanceResult
distance result
Definition: collision_data.h:420
transform.h
geometric_shape_to_BVH_model.h
hpp::fcl::generateBVHModel
void generateBVHModel(BVHModel< BV > &model, const Box &shape, const Transform3f &pose)
Generate BVH model from box.
Definition: geometric_shape_to_BVH_model.h:50
geometric_shapes.h
c2
c2
hpp::fcl::Contact::penetration_depth
FCL_REAL penetration_depth
penetration depth
Definition: collision_data.h:80
hpp::fcl::CollisionResult::distance_lower_bound
FCL_REAL distance_lower_bound
Definition: collision_data.h:312
collision.h
hpp::fcl::Box
Center at zero point, axis aligned box.
Definition: shape/geometric_shapes.h:125


hpp-fcl
Author(s):
autogenerated on Fri Aug 2 2024 02:45:15