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 coal {
48 
49 #ifdef COAL_HAS_OCTOMAP
50 
51 template <typename TypeA, typename TypeB>
52 std::size_t OctreeCollide(const CollisionGeometry* o1, const Transform3s& tf1,
53  const CollisionGeometry* o2, const Transform3s& tf2,
54  const GJKSolver* nsolver,
55  const CollisionRequest& request,
56  CollisionResult& result) {
57  if (request.isSatisfied(result)) return result.numContacts();
58 
59  if (request.security_margin < 0)
60  COAL_THROW_PRETTY("Negative security margin are not handled yet for Octree",
61  std::invalid_argument);
62 
63  typename TraversalTraitsCollision<TypeA, TypeB>::CollisionTraversal_t node(
64  request);
65  const TypeA* obj1 = dynamic_cast<const TypeA*>(o1);
66  const TypeB* obj2 = dynamic_cast<const TypeB*>(o2);
67  OcTreeSolver otsolver(nsolver);
68 
69  initialize(node, *obj1, tf1, *obj2, tf2, &otsolver, result);
70  collide(&node, request, result);
71 
72  return result.numContacts();
73 }
74 
75 #endif
76 
77 namespace details {
78 template <typename T_BVH, typename T_SH>
80  enum { Options = RelativeTransformationIsIdentity };
81 };
82 #define BVH_SHAPE_DEFAULT_TO_ORIENTED(bv) \
83  template <typename T_SH> \
84  struct bvh_shape_traits<bv, T_SH> { \
85  enum { Options = 0 }; \
86  }
91 #undef BVH_SHAPE_DEFAULT_TO_ORIENTED
92 } // namespace details
93 
98 template <typename T_BVH, typename T_SH,
100 struct COAL_LOCAL BVHShapeCollider{static std::size_t collide(
101  const CollisionGeometry* o1, const Transform3s& tf1,
102  const CollisionGeometry* o2, const Transform3s& tf2,
103  const GJKSolver* nsolver, const CollisionRequest& request,
104  CollisionResult& result){
105  if (request.isSatisfied(result)) return result.numContacts();
106 
107 if (request.security_margin < 0)
108  COAL_THROW_PRETTY("Negative security margin are not handled yet for BVHModel",
109  std::invalid_argument);
110 
111 if (_Options & RelativeTransformationIsIdentity)
112  return aligned(o1, tf1, o2, tf2, nsolver, request, result);
113 else
114  return oriented(o1, tf1, o2, tf2, nsolver, request, result);
115 } // namespace coal
116 
117 static std::size_t aligned(const CollisionGeometry* o1, const Transform3s& tf1,
118  const CollisionGeometry* o2, const Transform3s& tf2,
119  const GJKSolver* nsolver,
120  const CollisionRequest& request,
121  CollisionResult& result) {
122  if (request.isSatisfied(result)) return result.numContacts();
123 
124  MeshShapeCollisionTraversalNode<T_BVH, T_SH, RelativeTransformationIsIdentity>
125  node(request);
126  const BVHModel<T_BVH>* obj1 = static_cast<const BVHModel<T_BVH>*>(o1);
127  BVHModel<T_BVH>* obj1_tmp = new BVHModel<T_BVH>(*obj1);
128  Transform3s tf1_tmp = tf1;
129  const T_SH* obj2 = static_cast<const T_SH*>(o2);
130 
131  initialize(node, *obj1_tmp, tf1_tmp, *obj2, tf2, nsolver, result);
132  coal::collide(&node, request, result);
133 
134  delete obj1_tmp;
135  return result.numContacts();
136 }
137 
138 static std::size_t oriented(const CollisionGeometry* o1, const Transform3s& tf1,
139  const CollisionGeometry* o2, const Transform3s& tf2,
140  const GJKSolver* nsolver,
141  const CollisionRequest& request,
142  CollisionResult& result) {
143  if (request.isSatisfied(result)) return result.numContacts();
144 
145  MeshShapeCollisionTraversalNode<T_BVH, T_SH, 0> node(request);
146  const BVHModel<T_BVH>* obj1 = static_cast<const BVHModel<T_BVH>*>(o1);
147  const T_SH* obj2 = static_cast<const T_SH*>(o2);
148 
149  initialize(node, *obj1, tf1, *obj2, tf2, nsolver, result);
150  coal::collide(&node, request, result);
151  return result.numContacts();
152 }
153 }
154 ;
155 
161 template <typename BV, typename Shape>
162 struct COAL_LOCAL HeightFieldShapeCollider {
164 
165  static std::size_t collide(const CollisionGeometry* o1,
166  const Transform3s& tf1,
167  const CollisionGeometry* o2,
168  const Transform3s& tf2, const GJKSolver* nsolver,
169  const CollisionRequest& request,
170  CollisionResult& result) {
171  if (request.isSatisfied(result)) return result.numContacts();
172 
173  const HF& height_field = static_cast<const HF&>(*o1);
174  const Shape& shape = static_cast<const Shape&>(*o2);
175 
176  HeightFieldShapeCollisionTraversalNode<BV, Shape, 0> node(request);
177 
178  initialize(node, height_field, tf1, shape, tf2, nsolver, result);
179  coal::collide(&node, request, result);
180  return result.numContacts();
181  }
182 };
183 
184 namespace details {
185 template <typename OrientedMeshCollisionTraversalNode, typename T_BVH>
187  const Transform3s& tf1,
188  const CollisionGeometry* o2,
189  const Transform3s& tf2,
190  const CollisionRequest& request,
191  CollisionResult& result) {
192  if (request.isSatisfied(result)) return result.numContacts();
193 
194  OrientedMeshCollisionTraversalNode node(request);
195  const BVHModel<T_BVH>* obj1 = static_cast<const BVHModel<T_BVH>*>(o1);
196  const BVHModel<T_BVH>* obj2 = static_cast<const BVHModel<T_BVH>*>(o2);
197 
198  initialize(node, *obj1, tf1, *obj2, tf2, result);
199  collide(&node, request, result);
200 
201  return result.numContacts();
202 }
203 
204 } // namespace details
205 
206 template <typename T_BVH>
207 std::size_t BVHCollide(const CollisionGeometry* o1, const Transform3s& tf1,
208  const CollisionGeometry* o2, const Transform3s& tf2,
209  const CollisionRequest& request,
210  CollisionResult& result) {
211  if (request.isSatisfied(result)) return result.numContacts();
212 
213  // TODO(louis): each time we call collide on BVH-BVH, we:
214  // - Allocate 2 new BVHs
215  // - Copy and transform the vertices in both BVHs so that they are in the
216  // same frame
217  // - Recompute BVs of the BVH structure
218  // -> all that just to avoid doing (a few) rotations/translations of AABBs.
219  // Is it really worth it?
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  Transform3s tf1_tmp = tf1;
225  BVHModel<T_BVH>* obj2_tmp = new BVHModel<T_BVH>(*obj2);
226  Transform3s tf2_tmp = tf2;
227 
228  initialize(node, *obj1_tmp, tf1_tmp, *obj2_tmp, tf2_tmp, result);
229  coal::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 Transform3s& tf1,
239  const CollisionGeometry* o2, const Transform3s& 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 Transform3s& tf1,
249  const CollisionGeometry* o2,
250  const Transform3s& 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 Transform3s& tf1,
260  const CollisionGeometry* o2,
261  const Transform3s& 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 Transform3s& tf1,
270  const CollisionGeometry* o2, const Transform3s& 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>;
294  &ShapeShapeCollide<Box, TriangleP>;
295 
296  collision_matrix[GEOM_SPHERE][GEOM_BOX] = &ShapeShapeCollide<Sphere, Box>;
298  &ShapeShapeCollide<Sphere, Sphere>;
300  &ShapeShapeCollide<Sphere, Capsule>;
301  collision_matrix[GEOM_SPHERE][GEOM_CONE] = &ShapeShapeCollide<Sphere, Cone>;
303  &ShapeShapeCollide<Sphere, Cylinder>;
305  &ShapeShapeCollide<Sphere, ConvexBase>;
306  collision_matrix[GEOM_SPHERE][GEOM_PLANE] = &ShapeShapeCollide<Sphere, Plane>;
308  &ShapeShapeCollide<Sphere, Halfspace>;
310  &ShapeShapeCollide<Sphere, Ellipsoid>;
312  &ShapeShapeCollide<Sphere, TriangleP>;
313 
315  &ShapeShapeCollide<Ellipsoid, Box>;
317  &ShapeShapeCollide<Ellipsoid, Sphere>;
319  &ShapeShapeCollide<Ellipsoid, Capsule>;
321  &ShapeShapeCollide<Ellipsoid, Cone>;
323  &ShapeShapeCollide<Ellipsoid, Cylinder>;
325  &ShapeShapeCollide<Ellipsoid, ConvexBase>;
327  &ShapeShapeCollide<Ellipsoid, Plane>;
329  &ShapeShapeCollide<Ellipsoid, Halfspace>;
331  &ShapeShapeCollide<Ellipsoid, Ellipsoid>;
333  &ShapeShapeCollide<Ellipsoid, TriangleP>;
334 
335  collision_matrix[GEOM_CAPSULE][GEOM_BOX] = &ShapeShapeCollide<Capsule, Box>;
337  &ShapeShapeCollide<Capsule, Sphere>;
339  &ShapeShapeCollide<Capsule, Capsule>;
340  collision_matrix[GEOM_CAPSULE][GEOM_CONE] = &ShapeShapeCollide<Capsule, Cone>;
342  &ShapeShapeCollide<Capsule, Cylinder>;
344  &ShapeShapeCollide<Capsule, ConvexBase>;
346  &ShapeShapeCollide<Capsule, Plane>;
348  &ShapeShapeCollide<Capsule, Halfspace>;
350  &ShapeShapeCollide<Capsule, Ellipsoid>;
352  &ShapeShapeCollide<Capsule, TriangleP>;
353 
354  collision_matrix[GEOM_CONE][GEOM_BOX] = &ShapeShapeCollide<Cone, Box>;
355  collision_matrix[GEOM_CONE][GEOM_SPHERE] = &ShapeShapeCollide<Cone, Sphere>;
356  collision_matrix[GEOM_CONE][GEOM_CAPSULE] = &ShapeShapeCollide<Cone, Capsule>;
357  collision_matrix[GEOM_CONE][GEOM_CONE] = &ShapeShapeCollide<Cone, Cone>;
359  &ShapeShapeCollide<Cone, Cylinder>;
361  &ShapeShapeCollide<Cone, ConvexBase>;
362  collision_matrix[GEOM_CONE][GEOM_PLANE] = &ShapeShapeCollide<Cone, Plane>;
364  &ShapeShapeCollide<Cone, Halfspace>;
366  &ShapeShapeCollide<Cone, Ellipsoid>;
368  &ShapeShapeCollide<Cone, TriangleP>;
369 
370  collision_matrix[GEOM_CYLINDER][GEOM_BOX] = &ShapeShapeCollide<Cylinder, Box>;
372  &ShapeShapeCollide<Cylinder, Sphere>;
374  &ShapeShapeCollide<Cylinder, Capsule>;
376  &ShapeShapeCollide<Cylinder, Cone>;
378  &ShapeShapeCollide<Cylinder, Cylinder>;
380  &ShapeShapeCollide<Cylinder, ConvexBase>;
382  &ShapeShapeCollide<Cylinder, Plane>;
384  &ShapeShapeCollide<Cylinder, Halfspace>;
386  &ShapeShapeCollide<Cylinder, Ellipsoid>;
388  &ShapeShapeCollide<Cylinder, TriangleP>;
389 
390  collision_matrix[GEOM_CONVEX][GEOM_BOX] = &ShapeShapeCollide<ConvexBase, Box>;
392  &ShapeShapeCollide<ConvexBase, Sphere>;
394  &ShapeShapeCollide<ConvexBase, Capsule>;
396  &ShapeShapeCollide<ConvexBase, Cone>;
398  &ShapeShapeCollide<ConvexBase, Cylinder>;
400  &ShapeShapeCollide<ConvexBase, ConvexBase>;
402  &ShapeShapeCollide<ConvexBase, Plane>;
404  &ShapeShapeCollide<ConvexBase, Halfspace>;
406  &ShapeShapeCollide<ConvexBase, Ellipsoid>;
408  &ShapeShapeCollide<ConvexBase, TriangleP>;
409 
410  collision_matrix[GEOM_PLANE][GEOM_BOX] = &ShapeShapeCollide<Plane, Box>;
411  collision_matrix[GEOM_PLANE][GEOM_SPHERE] = &ShapeShapeCollide<Plane, Sphere>;
413  &ShapeShapeCollide<Plane, Capsule>;
414  collision_matrix[GEOM_PLANE][GEOM_CONE] = &ShapeShapeCollide<Plane, Cone>;
416  &ShapeShapeCollide<Plane, Cylinder>;
418  &ShapeShapeCollide<Plane, ConvexBase>;
419  collision_matrix[GEOM_PLANE][GEOM_PLANE] = &ShapeShapeCollide<Plane, Plane>;
421  &ShapeShapeCollide<Plane, Halfspace>;
423  &ShapeShapeCollide<Plane, Ellipsoid>;
425  &ShapeShapeCollide<Plane, TriangleP>;
426 
428  &ShapeShapeCollide<Halfspace, Box>;
430  &ShapeShapeCollide<Halfspace, Sphere>;
432  &ShapeShapeCollide<Halfspace, Capsule>;
434  &ShapeShapeCollide<Halfspace, Cone>;
436  &ShapeShapeCollide<Halfspace, Cylinder>;
438  &ShapeShapeCollide<Halfspace, ConvexBase>;
440  &ShapeShapeCollide<Halfspace, Plane>;
442  &ShapeShapeCollide<Halfspace, Halfspace>;
444  &ShapeShapeCollide<Halfspace, Ellipsoid>;
446  &ShapeShapeCollide<Halfspace, TriangleP>;
447 
449  &ShapeShapeCollide<TriangleP, Box>;
451  &ShapeShapeCollide<TriangleP, Sphere>;
453  &ShapeShapeCollide<TriangleP, Capsule>;
455  &ShapeShapeCollide<TriangleP, Cone>;
457  &ShapeShapeCollide<TriangleP, Cylinder>;
459  &ShapeShapeCollide<TriangleP, ConvexBase>;
461  &ShapeShapeCollide<TriangleP, Plane>;
463  &ShapeShapeCollide<TriangleP, Halfspace>;
465  &ShapeShapeCollide<TriangleP, Ellipsoid>;
467  &ShapeShapeCollide<TriangleP, TriangleP>;
468 
485 
501 
517 
536 
555 
574 
591 
610 
629 
648 
649  collision_matrix[BV_AABB][BV_AABB] = &BVHCollide<AABB>;
651  collision_matrix[BV_RSS][BV_RSS] = &BVHCollide<RSS>;
652  collision_matrix[BV_KDOP16][BV_KDOP16] = &BVHCollide<KDOP<16> >;
653  collision_matrix[BV_KDOP18][BV_KDOP18] = &BVHCollide<KDOP<18> >;
654  collision_matrix[BV_KDOP24][BV_KDOP24] = &BVHCollide<KDOP<24> >;
657 
658 #ifdef COAL_HAS_OCTOMAP
659  collision_matrix[GEOM_OCTREE][GEOM_BOX] = &OctreeCollide<OcTree, Box>;
660  collision_matrix[GEOM_OCTREE][GEOM_SPHERE] = &OctreeCollide<OcTree, Sphere>;
661  collision_matrix[GEOM_OCTREE][GEOM_CAPSULE] = &OctreeCollide<OcTree, Capsule>;
662  collision_matrix[GEOM_OCTREE][GEOM_CONE] = &OctreeCollide<OcTree, Cone>;
664  &OctreeCollide<OcTree, Cylinder>;
666  &OctreeCollide<OcTree, ConvexBase>;
667  collision_matrix[GEOM_OCTREE][GEOM_PLANE] = &OctreeCollide<OcTree, Plane>;
669  &OctreeCollide<OcTree, Halfspace>;
671  &OctreeCollide<OcTree, Ellipsoid>;
672 
673  collision_matrix[GEOM_BOX][GEOM_OCTREE] = &OctreeCollide<Box, OcTree>;
674  collision_matrix[GEOM_SPHERE][GEOM_OCTREE] = &OctreeCollide<Sphere, OcTree>;
675  collision_matrix[GEOM_CAPSULE][GEOM_OCTREE] = &OctreeCollide<Capsule, OcTree>;
676  collision_matrix[GEOM_CONE][GEOM_OCTREE] = &OctreeCollide<Cone, OcTree>;
678  &OctreeCollide<Cylinder, OcTree>;
680  &OctreeCollide<ConvexBase, OcTree>;
681  collision_matrix[GEOM_PLANE][GEOM_OCTREE] = &OctreeCollide<Plane, OcTree>;
683  &OctreeCollide<Halfspace, OcTree>;
684 
685  collision_matrix[GEOM_OCTREE][GEOM_OCTREE] = &OctreeCollide<OcTree, OcTree>;
686 
688  &OctreeCollide<OcTree, BVHModel<AABB> >;
690  &OctreeCollide<OcTree, BVHModel<OBB> >;
692  &OctreeCollide<OcTree, BVHModel<RSS> >;
694  &OctreeCollide<OcTree, BVHModel<OBBRSS> >;
696  &OctreeCollide<OcTree, BVHModel<kIOS> >;
698  &OctreeCollide<OcTree, BVHModel<KDOP<16> > >;
700  &OctreeCollide<OcTree, BVHModel<KDOP<18> > >;
702  &OctreeCollide<OcTree, BVHModel<KDOP<24> > >;
704  &OctreeCollide<OcTree, HeightField<AABB> >;
706  &OctreeCollide<OcTree, HeightField<OBBRSS> >;
707 
709  &OctreeCollide<BVHModel<AABB>, OcTree>;
710  collision_matrix[BV_OBB][GEOM_OCTREE] = &OctreeCollide<BVHModel<OBB>, OcTree>;
711  collision_matrix[BV_RSS][GEOM_OCTREE] = &OctreeCollide<BVHModel<RSS>, OcTree>;
713  &OctreeCollide<BVHModel<OBBRSS>, OcTree>;
715  &OctreeCollide<BVHModel<kIOS>, OcTree>;
717  &OctreeCollide<BVHModel<KDOP<16> >, OcTree>;
719  &OctreeCollide<BVHModel<KDOP<18> >, OcTree>;
721  &OctreeCollide<BVHModel<KDOP<24> >, OcTree>;
723  &OctreeCollide<HeightField<AABB>, OcTree>;
725  &OctreeCollide<HeightField<OBBRSS>, OcTree>;
726 #endif
727 }
728 // template struct CollisionFunctionMatrix;
729 } // namespace coal
coal::details::orientedMeshCollide
std::size_t orientedMeshCollide(const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:186
coal::BVHShapeCollider::aligned
static std::size_t aligned(const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const GJKSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:117
coal::CollisionFunctionMatrix::CollisionFunctionMatrix
CollisionFunctionMatrix()
Definition: collision_func_matrix.cpp:277
coal::BV_AABB
@ BV_AABB
Definition: coal/collision_object.h:66
coal::details::bvh_shape_traits
Definition: collision_func_matrix.cpp:79
coal::BV_KDOP24
@ BV_KDOP24
Definition: coal/collision_object.h:73
coal::NODE_COUNT
@ NODE_COUNT
Definition: coal/collision_object.h:87
coal::BV_kIOS
@ BV_kIOS
Definition: coal/collision_object.h:69
coal::BV_OBBRSS
@ BV_OBBRSS
Definition: coal/collision_object.h:70
coal::GEOM_CONE
@ GEOM_CONE
Definition: coal/collision_object.h:77
coal::Halfspace
Half Space: this is equivalent to the Plane in ODE. A Half space has a priviledged direction: the dir...
Definition: coal/shape/geometric_shapes.h:892
coal::GEOM_CONVEX
@ GEOM_CONVEX
Definition: coal/collision_object.h:79
gjk.tf1
tuple tf1
Definition: test/scripts/gjk.py:27
coal::CollisionRequest::security_margin
CoalScalar security_margin
Distance below which objects are considered in collision. See Collision.
Definition: coal/collision_data.h:328
coal::Capsule
Capsule It is where is the distance between the point x and the capsule segment AB,...
Definition: coal/shape/geometric_shapes.h:383
coal::BV_RSS
@ BV_RSS
Definition: coal/collision_object.h:68
coal::HeightFieldShapeCollider::collide
static std::size_t collide(const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const GJKSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:165
coal::details::bvh_shape_traits::Options
@ Options
Definition: collision_func_matrix.cpp:80
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
narrowphase.h
coal::BVHCollide< OBB >
std::size_t BVHCollide< OBB >(const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:238
coal::BVHCollide
std::size_t BVHCollide(const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:207
coal::GEOM_CAPSULE
@ GEOM_CAPSULE
Definition: coal/collision_object.h:76
coal::HeightFieldShapeCollider
Collider functor for HeightField data structure.
Definition: collision_func_matrix.cpp:162
coal::GJKSolver
collision and distance solver based on the GJK and EPA algorithms. Originally, GJK and EPA were imple...
Definition: coal/narrowphase/narrowphase.h:57
coal::BV_KDOP18
@ BV_KDOP18
Definition: coal/collision_object.h:72
coal::Ellipsoid
Ellipsoid centered at point zero.
Definition: coal/shape/geometric_shapes.h:305
coal::GEOM_SPHERE
@ GEOM_SPHERE
Definition: coal/collision_object.h:75
coal::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: coal/collision_object.h:94
coal::Plane
Infinite plane. A plane can be viewed as two half spaces; it has no priviledged direction....
Definition: coal/shape/geometric_shapes.h:983
coal::Box
Center at zero point, axis aligned box.
Definition: coal/shape/geometric_shapes.h:166
coal::Sphere
Center at zero point sphere.
Definition: coal/shape/geometric_shapes.h:240
traversal_node_setup.h
coal::Transform3s
Simple transform class used locally by InterpMotion.
Definition: coal/math/transform.h:55
coal::HF_AABB
@ HF_AABB
Definition: coal/collision_object.h:85
shape_shape_func.h
coal::GEOM_PLANE
@ GEOM_PLANE
Definition: coal/collision_object.h:80
coal::GEOM_ELLIPSOID
@ GEOM_ELLIPSOID
Definition: coal/collision_object.h:84
coal::GEOM_HALFSPACE
@ GEOM_HALFSPACE
Definition: coal/collision_object.h:81
COAL_THROW_PRETTY
#define COAL_THROW_PRETTY(message, exception)
Definition: include/coal/fwd.hh:64
coal::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: coal/collision_func_matrix.h:70
coal::CollisionRequest::isSatisfied
COAL_COMPILER_DIAGNOSTIC_POP bool isSatisfied(const CollisionResult &result) const
Definition: collision_data.cpp:43
coal::CollisionResult
collision result
Definition: coal/collision_data.h:390
coal::BVHShapeCollider::oriented
static std::size_t oriented(const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const GJKSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:138
geometric_shapes_traits.h
coal::BVHShapeCollider
Definition: collision_func_matrix.cpp:100
coal::GEOM_TRIANGLE
@ GEOM_TRIANGLE
Definition: coal/collision_object.h:82
coal::CollisionRequest
request to the collision algorithm
Definition: coal/collision_data.h:311
gjk.tf2
tuple tf2
Definition: test/scripts/gjk.py:36
coal::Cylinder
Cylinder along Z axis. The cylinder is defined at its centroid.
Definition: coal/shape/geometric_shapes.h:560
coal::BVHShapeCollider::collide
static std::size_t collide(const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const GJKSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:100
coal::HeightField
Data structure depicting a height field given by the base grid dimensions and the elevation along the...
Definition: coal/hfield.h:202
collision_func_matrix.h
coal::details::BVH_SHAPE_DEFAULT_TO_ORIENTED
BVH_SHAPE_DEFAULT_TO_ORIENTED(OBB)
coal::GEOM_CYLINDER
@ GEOM_CYLINDER
Definition: coal/collision_object.h:78
coal::Cone
Cone The base of the cone is at and the top is at .
Definition: coal/shape/geometric_shapes.h:467
coal::GEOM_OCTREE
@ GEOM_OCTREE
Definition: coal/collision_object.h:83
coal::BVHModel
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: coal/BVH/BVH_model.h:314
coal::OcTree
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
Definition: coal/octree.h:53
coal::BVHCollide< kIOS >
std::size_t BVHCollide< kIOS >(const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:258
coal::HeightFieldShapeCollider::HF
HeightField< BV > HF
Definition: collision_func_matrix.cpp:163
coal::collide
COAL_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:61
coal::BV_OBB
@ BV_OBB
Definition: coal/collision_object.h:67
coal::GEOM_BOX
@ GEOM_BOX
Definition: coal/collision_object.h:74
coal::HF_OBBRSS
@ HF_OBBRSS
Definition: coal/collision_object.h:86
coal::BVHCollide< OBBRSS >
std::size_t BVHCollide< OBBRSS >(const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const CollisionRequest &request, CollisionResult &result)
Definition: collision_func_matrix.cpp:247
initialize
bool initialize(MeshCollisionTraversalNode< BV, RelativeTransformationIsIdentity > &node, BVHModel< BV > &model1, Transform3s &tf1, BVHModel< BV > &model2, Transform3s &tf2, CollisionResult &result, bool use_refit=false, bool refit_bottomup=false)
Initialize traversal node for collision between two meshes, given the current transforms.
Definition: coal/internal/traversal_node_setup.h:467
coal::BV_KDOP16
@ BV_KDOP16
Definition: coal/collision_object.h:71
coal::ConvexBase
Base for convex polytope.
Definition: coal/shape/geometric_shapes.h:645
coal::CollisionResult::numContacts
size_t numContacts() const
number of contacts found
Definition: coal/collision_data.h:446


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:57