collision_func_matrix.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2015, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
39 
41 #include <../src/collision_node.h>
45 #include <../src/traits_traversal.h>
46 
47 namespace hpp {
48 namespace fcl {
49 
50 #ifdef HPP_FCL_HAS_OCTOMAP
51 
52 template <typename TypeA, typename TypeB>
53 std::size_t OctreeCollide(const CollisionGeometry* o1, const Transform3f& tf1,
54  const CollisionGeometry* o2, const Transform3f& tf2,
55  const GJKSolver* nsolver,
56  const CollisionRequest& request,
57  CollisionResult& result) {
58  if (request.isSatisfied(result)) return result.numContacts();
59 
60  if (request.security_margin < 0)
62  "Negative security margin are not handled yet for Octree",
63  std::invalid_argument);
64 
65  typename TraversalTraitsCollision<TypeA, TypeB>::CollisionTraversal_t node(
66  request);
67  const TypeA* obj1 = dynamic_cast<const TypeA*>(o1);
68  const TypeB* obj2 = dynamic_cast<const TypeB*>(o2);
69  OcTreeSolver otsolver(nsolver);
70 
71  initialize(node, *obj1, tf1, *obj2, tf2, &otsolver, result);
72  collide(&node, request, result);
73 
74  return result.numContacts();
75 }
76 
77 #endif
78 
79 namespace details {
80 template <typename T_BVH, typename T_SH>
82  enum { Options = RelativeTransformationIsIdentity };
83 };
84 #define BVH_SHAPE_DEFAULT_TO_ORIENTED(bv) \
85  template <typename T_SH> \
86  struct bvh_shape_traits<bv, T_SH> { \
87  enum { Options = 0 }; \
88  }
93 #undef BVH_SHAPE_DEFAULT_TO_ORIENTED
94 } // namespace details
95 
100 template <typename T_BVH, typename T_SH,
102 struct HPP_FCL_LOCAL BVHShapeCollider {
103  static std::size_t collide(const CollisionGeometry* o1,
104  const Transform3f& tf1,
105  const CollisionGeometry* o2,
106  const Transform3f& tf2, const GJKSolver* nsolver,
107  const CollisionRequest& request,
108  CollisionResult& result) {
109  if (request.isSatisfied(result)) return result.numContacts();
110 
111  if (request.security_margin < 0)
113  "Negative security margin are not handled yet for BVHModel",
114  std::invalid_argument);
115 
116  if (_Options & RelativeTransformationIsIdentity)
117  return aligned(o1, tf1, o2, tf2, nsolver, request, result);
118  else
119  return oriented(o1, tf1, o2, tf2, nsolver, request, result);
120  }
121 
122  static std::size_t aligned(const CollisionGeometry* o1,
123  const Transform3f& tf1,
124  const CollisionGeometry* o2,
125  const Transform3f& tf2, const GJKSolver* nsolver,
126  const CollisionRequest& request,
127  CollisionResult& result) {
128  if (request.isSatisfied(result)) return result.numContacts();
129 
130  MeshShapeCollisionTraversalNode<T_BVH, T_SH,
131  RelativeTransformationIsIdentity>
132  node(request);
133  const BVHModel<T_BVH>* obj1 = static_cast<const BVHModel<T_BVH>*>(o1);
134  BVHModel<T_BVH>* obj1_tmp = new BVHModel<T_BVH>(*obj1);
135  Transform3f tf1_tmp = tf1;
136  const T_SH* obj2 = static_cast<const T_SH*>(o2);
137 
138  initialize(node, *obj1_tmp, tf1_tmp, *obj2, tf2, nsolver, result);
139  fcl::collide(&node, request, result);
140 
141  delete obj1_tmp;
142  return result.numContacts();
143  }
144 
145  static std::size_t oriented(const CollisionGeometry* o1,
146  const Transform3f& tf1,
147  const CollisionGeometry* o2,
148  const Transform3f& tf2, const GJKSolver* nsolver,
149  const CollisionRequest& request,
150  CollisionResult& result) {
151  if (request.isSatisfied(result)) return result.numContacts();
152 
153  MeshShapeCollisionTraversalNode<T_BVH, T_SH, 0> node(request);
154  const BVHModel<T_BVH>* obj1 = static_cast<const BVHModel<T_BVH>*>(o1);
155  const T_SH* obj2 = static_cast<const T_SH*>(o2);
156 
157  initialize(node, *obj1, tf1, *obj2, tf2, nsolver, result);
158  fcl::collide(&node, request, result);
159  return result.numContacts();
160  }
161 };
162 
168 template <typename BV, typename Shape>
169 struct HPP_FCL_LOCAL HeightFieldShapeCollider {
171 
172  static std::size_t collide(const CollisionGeometry* o1,
173  const Transform3f& tf1,
174  const CollisionGeometry* o2,
175  const Transform3f& tf2, const GJKSolver* nsolver,
176  const CollisionRequest& request,
177  CollisionResult& result) {
178  if (request.isSatisfied(result)) return result.numContacts();
179 
180  const HF& height_field = static_cast<const HF&>(*o1);
181  const Shape& shape = static_cast<const Shape&>(*o2);
182 
183  HeightFieldShapeCollisionTraversalNode<BV, Shape, 0> node(request);
184 
185  initialize(node, height_field, tf1, shape, tf2, nsolver, result);
186  fcl::collide(&node, request, result);
187  return result.numContacts();
188  }
189 };
190 
191 namespace details {
192 template <typename OrientedMeshCollisionTraversalNode, typename T_BVH>
194  const Transform3f& tf1,
195  const CollisionGeometry* o2,
196  const Transform3f& tf2,
197  const CollisionRequest& request,
198  CollisionResult& result) {
199  if (request.isSatisfied(result)) return result.numContacts();
200 
201  OrientedMeshCollisionTraversalNode node(request);
202  const BVHModel<T_BVH>* obj1 = static_cast<const BVHModel<T_BVH>*>(o1);
203  const BVHModel<T_BVH>* obj2 = static_cast<const BVHModel<T_BVH>*>(o2);
204 
205  initialize(node, *obj1, tf1, *obj2, tf2, result);
206  collide(&node, request, result);
207 
208  return result.numContacts();
209 }
210 
211 } // namespace details
212 
213 template <typename T_BVH>
214 std::size_t BVHCollide(const CollisionGeometry* o1, const Transform3f& tf1,
215  const CollisionGeometry* o2, const Transform3f& tf2,
216  const CollisionRequest& request,
217  CollisionResult& result) {
218  if (request.isSatisfied(result)) return result.numContacts();
219 
220  MeshCollisionTraversalNode<T_BVH> node(request);
221  const BVHModel<T_BVH>* obj1 = static_cast<const BVHModel<T_BVH>*>(o1);
222  const BVHModel<T_BVH>* obj2 = static_cast<const BVHModel<T_BVH>*>(o2);
223  BVHModel<T_BVH>* obj1_tmp = new BVHModel<T_BVH>(*obj1);
224  Transform3f tf1_tmp = tf1;
225  BVHModel<T_BVH>* obj2_tmp = new BVHModel<T_BVH>(*obj2);
226  Transform3f tf2_tmp = tf2;
227 
228  initialize(node, *obj1_tmp, tf1_tmp, *obj2_tmp, tf2_tmp, result);
229  fcl::collide(&node, request, result);
230 
231  delete obj1_tmp;
232  delete obj2_tmp;
233 
234  return result.numContacts();
235 }
236 
237 template <>
238 std::size_t BVHCollide<OBB>(const CollisionGeometry* o1, const Transform3f& tf1,
239  const CollisionGeometry* o2, const Transform3f& tf2,
240  const CollisionRequest& request,
241  CollisionResult& result) {
242  return details::orientedMeshCollide<MeshCollisionTraversalNodeOBB, OBB>(
243  o1, tf1, o2, tf2, request, result);
244 }
245 
246 template <>
247 std::size_t BVHCollide<OBBRSS>(const CollisionGeometry* o1,
248  const Transform3f& tf1,
249  const CollisionGeometry* o2,
250  const Transform3f& tf2,
251  const CollisionRequest& request,
252  CollisionResult& result) {
253  return details::orientedMeshCollide<MeshCollisionTraversalNodeOBBRSS, OBBRSS>(
254  o1, tf1, o2, tf2, request, result);
255 }
256 
257 template <>
258 std::size_t BVHCollide<kIOS>(const CollisionGeometry* o1,
259  const Transform3f& tf1,
260  const CollisionGeometry* o2,
261  const Transform3f& tf2,
262  const CollisionRequest& request,
263  CollisionResult& result) {
264  return details::orientedMeshCollide<MeshCollisionTraversalNodekIOS, kIOS>(
265  o1, tf1, o2, tf2, request, result);
266 }
267 
268 template <typename T_BVH>
269 std::size_t BVHCollide(const CollisionGeometry* o1, const Transform3f& tf1,
270  const CollisionGeometry* o2, const Transform3f& tf2,
271  const GJKSolver* /*nsolver*/,
272  const CollisionRequest& request,
273  CollisionResult& result) {
274  return BVHCollide<T_BVH>(o1, tf1, o2, tf2, request, result);
275 }
276 
278  for (int i = 0; i < NODE_COUNT; ++i) {
279  for (int j = 0; j < NODE_COUNT; ++j) collision_matrix[i][j] = NULL;
280  }
281 
282  collision_matrix[GEOM_BOX][GEOM_BOX] = &ShapeShapeCollide<Box, Box>;
283  collision_matrix[GEOM_BOX][GEOM_SPHERE] = &ShapeShapeCollide<Box, Sphere>;
284  collision_matrix[GEOM_BOX][GEOM_CAPSULE] = &ShapeShapeCollide<Box, Capsule>;
285  collision_matrix[GEOM_BOX][GEOM_CONE] = &ShapeShapeCollide<Box, Cone>;
286  collision_matrix[GEOM_BOX][GEOM_CYLINDER] = &ShapeShapeCollide<Box, Cylinder>;
287  collision_matrix[GEOM_BOX][GEOM_CONVEX] = &ShapeShapeCollide<Box, ConvexBase>;
288  collision_matrix[GEOM_BOX][GEOM_PLANE] = &ShapeShapeCollide<Box, Plane>;
290  &ShapeShapeCollide<Box, Halfspace>;
292  &ShapeShapeCollide<Box, Ellipsoid>;
293 
294  collision_matrix[GEOM_SPHERE][GEOM_BOX] = &ShapeShapeCollide<Sphere, Box>;
296  &ShapeShapeCollide<Sphere, Sphere>;
298  &ShapeShapeCollide<Sphere, Capsule>;
299  collision_matrix[GEOM_SPHERE][GEOM_CONE] = &ShapeShapeCollide<Sphere, Cone>;
301  &ShapeShapeCollide<Sphere, Cylinder>;
303  &ShapeShapeCollide<Sphere, ConvexBase>;
304  collision_matrix[GEOM_SPHERE][GEOM_PLANE] = &ShapeShapeCollide<Sphere, Plane>;
306  &ShapeShapeCollide<Sphere, Halfspace>;
308  &ShapeShapeCollide<Sphere, Ellipsoid>;
309 
311  &ShapeShapeCollide<Ellipsoid, Box>;
313  &ShapeShapeCollide<Ellipsoid, Sphere>;
315  &ShapeShapeCollide<Ellipsoid, Capsule>;
317  &ShapeShapeCollide<Ellipsoid, Cone>;
319  &ShapeShapeCollide<Ellipsoid, Cylinder>;
321  &ShapeShapeCollide<Ellipsoid, ConvexBase>;
322  // TODO Louis: Ellipsoid - Plane
323  // TODO Louis: Ellipsoid - Halfspace
325  &ShapeShapeCollide<Ellipsoid, Ellipsoid>;
326 
327  collision_matrix[GEOM_CAPSULE][GEOM_BOX] = &ShapeShapeCollide<Capsule, Box>;
329  &ShapeShapeCollide<Capsule, Sphere>;
331  &ShapeShapeCollide<Capsule, Capsule>;
332  collision_matrix[GEOM_CAPSULE][GEOM_CONE] = &ShapeShapeCollide<Capsule, Cone>;
334  &ShapeShapeCollide<Capsule, Cylinder>;
336  &ShapeShapeCollide<Capsule, ConvexBase>;
338  &ShapeShapeCollide<Capsule, Plane>;
340  &ShapeShapeCollide<Capsule, Halfspace>;
342  &ShapeShapeCollide<Capsule, Ellipsoid>;
343 
344  collision_matrix[GEOM_CONE][GEOM_BOX] = &ShapeShapeCollide<Cone, Box>;
345  collision_matrix[GEOM_CONE][GEOM_SPHERE] = &ShapeShapeCollide<Cone, Sphere>;
346  collision_matrix[GEOM_CONE][GEOM_CAPSULE] = &ShapeShapeCollide<Cone, Capsule>;
347  collision_matrix[GEOM_CONE][GEOM_CONE] = &ShapeShapeCollide<Cone, Cone>;
349  &ShapeShapeCollide<Cone, Cylinder>;
351  &ShapeShapeCollide<Cone, ConvexBase>;
352  collision_matrix[GEOM_CONE][GEOM_PLANE] = &ShapeShapeCollide<Cone, Plane>;
354  &ShapeShapeCollide<Cone, Halfspace>;
356  &ShapeShapeCollide<Cone, Ellipsoid>;
357 
358  collision_matrix[GEOM_CYLINDER][GEOM_BOX] = &ShapeShapeCollide<Cylinder, Box>;
360  &ShapeShapeCollide<Cylinder, Sphere>;
362  &ShapeShapeCollide<Cylinder, Capsule>;
364  &ShapeShapeCollide<Cylinder, Cone>;
366  &ShapeShapeCollide<Cylinder, Cylinder>;
368  &ShapeShapeCollide<Cylinder, ConvexBase>;
370  &ShapeShapeCollide<Cylinder, Plane>;
372  &ShapeShapeCollide<Cylinder, Halfspace>;
374  &ShapeShapeCollide<Cylinder, Ellipsoid>;
375 
376  collision_matrix[GEOM_CONVEX][GEOM_BOX] = &ShapeShapeCollide<ConvexBase, Box>;
378  &ShapeShapeCollide<ConvexBase, Sphere>;
380  &ShapeShapeCollide<ConvexBase, Capsule>;
382  &ShapeShapeCollide<ConvexBase, Cone>;
384  &ShapeShapeCollide<ConvexBase, Cylinder>;
386  &ShapeShapeCollide<ConvexBase, ConvexBase>;
388  &ShapeShapeCollide<ConvexBase, Plane>;
390  &ShapeShapeCollide<ConvexBase, Halfspace>;
392  &ShapeShapeCollide<ConvexBase, Ellipsoid>;
393 
394  collision_matrix[GEOM_PLANE][GEOM_BOX] = &ShapeShapeCollide<Plane, Box>;
395  collision_matrix[GEOM_PLANE][GEOM_SPHERE] = &ShapeShapeCollide<Plane, Sphere>;
397  &ShapeShapeCollide<Plane, Capsule>;
398  collision_matrix[GEOM_PLANE][GEOM_CONE] = &ShapeShapeCollide<Plane, Cone>;
400  &ShapeShapeCollide<Plane, Cylinder>;
402  &ShapeShapeCollide<Plane, ConvexBase>;
403  collision_matrix[GEOM_PLANE][GEOM_PLANE] = &ShapeShapeCollide<Plane, Plane>;
405  &ShapeShapeCollide<Plane, Halfspace>;
406  // TODO Louis: Ellipsoid - Plane
407 
409  &ShapeShapeCollide<Halfspace, Box>;
411  &ShapeShapeCollide<Halfspace, Sphere>;
413  &ShapeShapeCollide<Halfspace, Capsule>;
415  &ShapeShapeCollide<Halfspace, Cone>;
417  &ShapeShapeCollide<Halfspace, Cylinder>;
419  &ShapeShapeCollide<Halfspace, ConvexBase>;
421  &ShapeShapeCollide<Halfspace, Plane>;
423  &ShapeShapeCollide<Halfspace, Halfspace>;
424  // TODO Louis: Ellipsoid - Halfspace
425 
442 
458 
474 
493 
512 
531 
548 
567 
586 
605 
606  collision_matrix[BV_AABB][BV_AABB] = &BVHCollide<AABB>;
608  collision_matrix[BV_RSS][BV_RSS] = &BVHCollide<RSS>;
609  collision_matrix[BV_KDOP16][BV_KDOP16] = &BVHCollide<KDOP<16> >;
610  collision_matrix[BV_KDOP18][BV_KDOP18] = &BVHCollide<KDOP<18> >;
611  collision_matrix[BV_KDOP24][BV_KDOP24] = &BVHCollide<KDOP<24> >;
614 
615 #ifdef HPP_FCL_HAS_OCTOMAP
616  collision_matrix[GEOM_OCTREE][GEOM_BOX] = &OctreeCollide<OcTree, Box>;
617  collision_matrix[GEOM_OCTREE][GEOM_SPHERE] = &OctreeCollide<OcTree, Sphere>;
618  collision_matrix[GEOM_OCTREE][GEOM_CAPSULE] = &OctreeCollide<OcTree, Capsule>;
619  collision_matrix[GEOM_OCTREE][GEOM_CONE] = &OctreeCollide<OcTree, Cone>;
621  &OctreeCollide<OcTree, Cylinder>;
623  &OctreeCollide<OcTree, ConvexBase>;
624  collision_matrix[GEOM_OCTREE][GEOM_PLANE] = &OctreeCollide<OcTree, Plane>;
626  &OctreeCollide<OcTree, Halfspace>;
628  &OctreeCollide<OcTree, Ellipsoid>;
629 
630  collision_matrix[GEOM_BOX][GEOM_OCTREE] = &OctreeCollide<Box, OcTree>;
631  collision_matrix[GEOM_SPHERE][GEOM_OCTREE] = &OctreeCollide<Sphere, OcTree>;
632  collision_matrix[GEOM_CAPSULE][GEOM_OCTREE] = &OctreeCollide<Capsule, OcTree>;
633  collision_matrix[GEOM_CONE][GEOM_OCTREE] = &OctreeCollide<Cone, OcTree>;
635  &OctreeCollide<Cylinder, OcTree>;
637  &OctreeCollide<ConvexBase, OcTree>;
638  collision_matrix[GEOM_PLANE][GEOM_OCTREE] = &OctreeCollide<Plane, OcTree>;
640  &OctreeCollide<Halfspace, OcTree>;
641 
642  collision_matrix[GEOM_OCTREE][GEOM_OCTREE] = &OctreeCollide<OcTree, OcTree>;
643 
645  &OctreeCollide<OcTree, BVHModel<AABB> >;
647  &OctreeCollide<OcTree, BVHModel<OBB> >;
649  &OctreeCollide<OcTree, BVHModel<RSS> >;
651  &OctreeCollide<OcTree, BVHModel<OBBRSS> >;
653  &OctreeCollide<OcTree, BVHModel<kIOS> >;
655  &OctreeCollide<OcTree, BVHModel<KDOP<16> > >;
657  &OctreeCollide<OcTree, BVHModel<KDOP<18> > >;
659  &OctreeCollide<OcTree, BVHModel<KDOP<24> > >;
660 
662  &OctreeCollide<BVHModel<AABB>, OcTree>;
663  collision_matrix[BV_OBB][GEOM_OCTREE] = &OctreeCollide<BVHModel<OBB>, OcTree>;
664  collision_matrix[BV_RSS][GEOM_OCTREE] = &OctreeCollide<BVHModel<RSS>, OcTree>;
666  &OctreeCollide<BVHModel<OBBRSS>, OcTree>;
668  &OctreeCollide<BVHModel<kIOS>, OcTree>;
670  &OctreeCollide<BVHModel<KDOP<16> >, OcTree>;
672  &OctreeCollide<BVHModel<KDOP<18> >, OcTree>;
674  &OctreeCollide<BVHModel<KDOP<24> >, OcTree>;
675 #endif
676 }
677 // template struct CollisionFunctionMatrix;
678 } // namespace fcl
679 
680 } // namespace hpp
hpp::fcl::HF_OBBRSS
@ HF_OBBRSS
Definition: collision_object.h:87
hpp::fcl::GEOM_HALFSPACE
@ GEOM_HALFSPACE
Definition: collision_object.h:82
collision_func_matrix.h
shape_shape_func.h
hpp::fcl::GEOM_ELLIPSOID
@ GEOM_ELLIPSOID
Definition: collision_object.h:85
hpp::fcl::GEOM_BOX
@ GEOM_BOX
Definition: collision_object.h:75
hpp::fcl::BVHCollide
std::size_t BVHCollide(const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:214
hpp::fcl::BV_KDOP24
@ BV_KDOP24
Definition: collision_object.h:74
hpp::fcl::GEOM_PLANE
@ GEOM_PLANE
Definition: collision_object.h:81
hpp::fcl::BVHCollide< OBBRSS >
std::size_t BVHCollide< OBBRSS >(const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:247
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::BV_RSS
@ BV_RSS
Definition: collision_object.h:69
hpp::fcl::HeightField
Data structure depicting a height field given by the base grid dimensions and the elevation along the...
Definition: hfield.h:182
initialize
bool initialize(MeshCollisionTraversalNode< BV, RelativeTransformationIsIdentity > &node, BVHModel< BV > &model1, Transform3f &tf1, BVHModel< BV > &model2, Transform3f &tf2, CollisionResult &result, bool use_refit=false, bool refit_bottomup=false)
Initialize traversal node for collision between two meshes, given the current transforms.
Definition: traversal_node_setup.h:423
hpp::fcl::CollisionResult::numContacts
size_t numContacts() const
number of contacts found
Definition: collision_data.h:342
hpp::fcl::GEOM_CONVEX
@ GEOM_CONVEX
Definition: collision_object.h:80
hpp::fcl::BVHCollide< kIOS >
std::size_t BVHCollide< kIOS >(const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:258
hpp::fcl::BV_OBB
@ BV_OBB
Definition: collision_object.h:68
hpp::fcl::BVHCollide< OBB >
std::size_t BVHCollide< OBB >(const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:238
hpp::fcl::HeightFieldShapeCollider::collide
static std::size_t collide(const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:172
hpp::fcl::NODE_COUNT
@ NODE_COUNT
Definition: collision_object.h:88
hpp::fcl::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: collision_object.h:95
hpp::fcl::Cylinder
Cylinder along Z axis. The cylinder is defined at its centroid.
Definition: shape/geometric_shapes.h:501
narrowphase.h
hpp::fcl::Ellipsoid
Ellipsoid centered at point zero.
Definition: shape/geometric_shapes.h:258
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
hpp::fcl::details::bvh_shape_traits
Definition: collision_func_matrix.cpp:81
hpp::fcl::BV_OBBRSS
@ BV_OBBRSS
Definition: collision_object.h:71
hpp::fcl::HeightFieldShapeCollider::HF
HeightField< BV > HF
Definition: collision_func_matrix.cpp:170
hpp::fcl::BV_AABB
@ BV_AABB
Definition: collision_object.h:67
details
Definition: traversal_node_setup.h:792
hpp::fcl::GJKSolver
collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the ...
Definition: narrowphase.h:54
hpp::fcl::CollisionRequest::security_margin
FCL_REAL security_margin
Distance below which objects are considered in collision. See Collision.
Definition: collision_data.h:251
hpp::fcl::CollisionFunctionMatrix::CollisionFunctionMatrix
CollisionFunctionMatrix()
Definition: collision_func_matrix.cpp:277
hpp::fcl::details::BVH_SHAPE_DEFAULT_TO_ORIENTED
BVH_SHAPE_DEFAULT_TO_ORIENTED(OBB)
hpp::fcl::details::orientedMeshCollide
std::size_t orientedMeshCollide(const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:193
hpp::fcl::GEOM_SPHERE
@ GEOM_SPHERE
Definition: collision_object.h:76
hpp
Main namespace.
Definition: broadphase_bruteforce.h:44
hpp::fcl::CollisionRequest
request to the collision algorithm
Definition: collision_data.h:235
hpp::fcl::BVHShapeCollider::oriented
static std::size_t oriented(const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:145
hpp::fcl::CollisionFunctionMatrix::collision_matrix
CollisionFunc collision_matrix[NODE_COUNT][NODE_COUNT]
each item in the collision matrix is a function to handle collision between objects of type1 and type...
Definition: collision_func_matrix.h:71
gjk.tf2
tuple tf2
Definition: test/scripts/gjk.py:36
hpp::fcl::CollisionResult
collision result
Definition: collision_data.h:302
hpp::fcl::Cone
Cone The base of the cone is at and the top is at .
Definition: shape/geometric_shapes.h:414
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::GEOM_OCTREE
@ GEOM_OCTREE
Definition: collision_object.h:84
HPP_FCL_THROW_PRETTY
#define HPP_FCL_THROW_PRETTY(message, exception)
Definition: include/hpp/fcl/fwd.hh:57
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::Halfspace
Half Space: this is equivalent to the Plane in ODE. The separation plane is defined as n * x = d; Poi...
Definition: shape/geometric_shapes.h:729
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::GEOM_CYLINDER
@ GEOM_CYLINDER
Definition: collision_object.h:79
hpp::fcl::BV_KDOP18
@ BV_KDOP18
Definition: collision_object.h:73
hpp::fcl::GEOM_CONE
@ GEOM_CONE
Definition: collision_object.h:78
hpp::fcl::CollisionRequest::isSatisfied
bool isSatisfied(const CollisionResult &result) const
Definition: collision_data.cpp:43
hpp::fcl::OcTree
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
Definition: octree.h:53
hpp::fcl::details::bvh_shape_traits::Options
@ Options
Definition: collision_func_matrix.cpp:82
geometric_shapes_traits.h
hpp::fcl::HeightFieldShapeCollider
Collider functor for HeightField data structure.
Definition: collision_func_matrix.cpp:169
hpp::fcl::BVHShapeCollider::collide
static std::size_t collide(const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:103
traversal_node_setup.h
hpp::fcl::BV_kIOS
@ BV_kIOS
Definition: collision_object.h:70
hpp::fcl::BVHShapeCollider::aligned
static std::size_t aligned(const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:122
hpp::fcl::BV_KDOP16
@ BV_KDOP16
Definition: collision_object.h:72
hpp::fcl::GEOM_CAPSULE
@ GEOM_CAPSULE
Definition: collision_object.h:77
hpp::fcl::HF_AABB
@ HF_AABB
Definition: collision_object.h:86
hpp::fcl::BVHShapeCollider
Definition: collision_func_matrix.cpp:102
hpp::fcl::Box
Center at zero point, axis aligned box.
Definition: shape/geometric_shapes.h:125
hpp::fcl::Plane
Infinite plane.
Definition: shape/geometric_shapes.h:810


hpp-fcl
Author(s):
autogenerated on Fri Jan 26 2024 03:46:13