38 #ifndef FCL_COLLISION_FUNC_MATRIX_INL_H 39 #define FCL_COLLISION_FUNC_MATRIX_INL_H 43 #include "fcl/config.h" 81 #endif // FCL_HAVE_OCTOMAP 92 template <
typename Shape,
typename NarrowPhaseSolver>
93 std::size_t ShapeOcTreeCollide(
94 const CollisionGeometry<typename Shape::S>* o1,
95 const Transform3<typename Shape::S>& tf1,
96 const CollisionGeometry<typename Shape::S>* o2,
97 const Transform3<typename Shape::S>& tf2,
98 const NarrowPhaseSolver* nsolver,
99 const CollisionRequest<typename Shape::S>& request,
100 CollisionResult<typename Shape::S>& result)
102 using S =
typename Shape::S;
104 if(request.isSatisfied(result))
return result.numContacts();
106 ShapeOcTreeCollisionTraversalNode<Shape, NarrowPhaseSolver> node;
107 const Shape*
obj1 =
static_cast<const Shape*
>(o1);
108 const OcTree<S>*
obj2 =
static_cast<const OcTree<S>*
>(o2);
109 OcTreeSolver<NarrowPhaseSolver> otsolver(nsolver);
111 initialize(node, *obj1, tf1, *obj2, tf2, &otsolver, request, result);
114 return result.numContacts();
118 template <
typename Shape,
typename NarrowPhaseSolver>
119 std::size_t OcTreeShapeCollide(
120 const CollisionGeometry<typename Shape::S>* o1,
121 const Transform3<typename Shape::S>& tf1,
122 const CollisionGeometry<typename Shape::S>* o2,
123 const Transform3<typename Shape::S>& tf2,
124 const NarrowPhaseSolver* nsolver,
125 const CollisionRequest<typename Shape::S>& request,
126 CollisionResult<typename Shape::S>& result)
128 using S =
typename Shape::S;
130 if(request.isSatisfied(result))
return result.numContacts();
132 OcTreeShapeCollisionTraversalNode<Shape, NarrowPhaseSolver> node;
133 const OcTree<S>* obj1 =
static_cast<const OcTree<S>*
>(o1);
134 const Shape* obj2 =
static_cast<const Shape*
>(o2);
135 OcTreeSolver<NarrowPhaseSolver> otsolver(nsolver);
137 initialize(node, *obj1, tf1, *obj2, tf2, &otsolver, request, result);
140 return result.numContacts();
144 template <
typename NarrowPhaseSolver>
145 std::size_t OcTreeCollide(
146 const CollisionGeometry<typename NarrowPhaseSolver::S>* o1,
147 const Transform3<typename NarrowPhaseSolver::S>& tf1,
148 const CollisionGeometry<typename NarrowPhaseSolver::S>* o2,
149 const Transform3<typename NarrowPhaseSolver::S>& tf2,
150 const NarrowPhaseSolver* nsolver,
151 const CollisionRequest<typename NarrowPhaseSolver::S>& request,
152 CollisionResult<typename NarrowPhaseSolver::S>& result)
154 using S =
typename NarrowPhaseSolver::S;
156 if(request.isSatisfied(result))
return result.numContacts();
158 OcTreeCollisionTraversalNode<NarrowPhaseSolver> node;
159 const OcTree<S>* obj1 =
static_cast<const OcTree<S>*
>(o1);
160 const OcTree<S>* obj2 =
static_cast<const OcTree<S>*
>(o2);
161 OcTreeSolver<NarrowPhaseSolver> otsolver(nsolver);
163 initialize(node, *obj1, tf1, *obj2, tf2, &otsolver, request, result);
166 return result.numContacts();
170 template <
typename BV,
typename NarrowPhaseSolver>
171 std::size_t OcTreeBVHCollide(
172 const CollisionGeometry<typename BV::S>* o1,
173 const Transform3<typename BV::S>& tf1,
174 const CollisionGeometry<typename BV::S>* o2,
175 const Transform3<typename BV::S>& tf2,
176 const NarrowPhaseSolver* nsolver,
177 const CollisionRequest<typename BV::S>& request,
178 CollisionResult<typename BV::S>& result)
180 using S =
typename BV::S;
182 if(request.isSatisfied(result))
return result.numContacts();
184 if(request.enable_cost && request.use_approximate_cost)
186 CollisionRequest<S> no_cost_request(request);
187 no_cost_request.enable_cost =
false;
189 OcTreeMeshCollisionTraversalNode<BV, NarrowPhaseSolver> node;
190 const OcTree<S>* obj1 =
static_cast<const OcTree<S>*
>(o1);
191 const BVHModel<BV>* obj2 =
static_cast<const BVHModel<BV>*
>(o2);
192 OcTreeSolver<NarrowPhaseSolver> otsolver(nsolver);
194 initialize(node, *obj1, tf1, *obj2, tf2, &otsolver, no_cost_request, result);
198 Transform3<S> box_tf;
201 box.cost_density = obj2->cost_density;
202 box.threshold_occupied = obj2->threshold_occupied;
203 box.threshold_free = obj2->threshold_free;
205 CollisionRequest<S> only_cost_request(result.numContacts(),
false, request.num_max_cost_sources,
true,
false);
206 OcTreeShapeCollide<Box<S>, NarrowPhaseSolver>(o1, tf1, &box, box_tf, nsolver, only_cost_request, result);
210 OcTreeMeshCollisionTraversalNode<BV, NarrowPhaseSolver> node;
211 const OcTree<S>* obj1 =
static_cast<const OcTree<S>*
>(o1);
212 const BVHModel<BV>* obj2 =
static_cast<const BVHModel<BV>*
>(o2);
213 OcTreeSolver<NarrowPhaseSolver> otsolver(nsolver);
215 initialize(node, *obj1, tf1, *obj2, tf2, &otsolver, request, result);
219 return result.numContacts();
223 template <
typename BV,
typename NarrowPhaseSolver>
224 std::size_t BVHOcTreeCollide(
225 const CollisionGeometry<typename BV::S>* o1,
226 const Transform3<typename BV::S>& tf1,
227 const CollisionGeometry<typename BV::S>* o2,
228 const Transform3<typename BV::S>& tf2,
229 const NarrowPhaseSolver* nsolver,
230 const CollisionRequest<typename BV::S>& request,
231 CollisionResult<typename BV::S>& result)
233 using S =
typename BV::S;
235 if(request.isSatisfied(result))
return result.numContacts();
237 if(request.enable_cost && request.use_approximate_cost)
239 CollisionRequest<S> no_cost_request(request);
240 no_cost_request.enable_cost =
false;
242 MeshOcTreeCollisionTraversalNode<BV, NarrowPhaseSolver> node;
243 const BVHModel<BV>* obj1 =
static_cast<const BVHModel<BV>*
>(o1);
244 const OcTree<S>* obj2 =
static_cast<const OcTree<S>*
>(o2);
245 OcTreeSolver<NarrowPhaseSolver> otsolver(nsolver);
247 initialize(node, *obj1, tf1, *obj2, tf2, &otsolver, no_cost_request, result);
251 Transform3<S> box_tf;
254 box.cost_density = obj1->cost_density;
255 box.threshold_occupied = obj1->threshold_occupied;
256 box.threshold_free = obj1->threshold_free;
258 CollisionRequest<S> only_cost_request(result.numContacts(),
false, request.num_max_cost_sources,
true,
false);
259 ShapeOcTreeCollide<Box<S>, NarrowPhaseSolver>(&box, box_tf, o2, tf2, nsolver, only_cost_request, result);
263 MeshOcTreeCollisionTraversalNode<BV, NarrowPhaseSolver> node;
264 const BVHModel<BV>* obj1 =
static_cast<const BVHModel<BV>*
>(o1);
265 const OcTree<S>* obj2 =
static_cast<const OcTree<S>*
>(o2);
266 OcTreeSolver<NarrowPhaseSolver> otsolver(nsolver);
268 initialize(node, *obj1, tf1, *obj2, tf2, &otsolver, request, result);
272 return result.numContacts();
278 template <
typename Shape1,
typename Shape2,
typename NarrowPhaseSolver>
284 const NarrowPhaseSolver* nsolver,
291 const Shape1* obj1 =
static_cast<const Shape1*
>(o1);
292 const Shape2* obj2 =
static_cast<const Shape2*
>(o2);
296 nsolver->enableCachedGuess(
true);
301 nsolver->enableCachedGuess(
true);
304 initialize(node, *obj1, tf1, *obj2, tf2, nsolver, request, result);
314 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
317 using S =
typename BV::S;
324 const NarrowPhaseSolver* nsolver,
339 const Shape* obj2 =
static_cast<const Shape*
>(o2);
341 initialize(node, *obj1_tmp, tf1_tmp, *obj2, tf2, nsolver, no_cost_request, result);
355 ShapeShapeCollide<Box<S>, Shape>(&box, box_tf, o2, tf2, nsolver, only_cost_request, result);
363 const Shape* obj2 =
static_cast<const Shape*
>(o2);
365 initialize(node, *obj1_tmp, tf1_tmp, *obj2, tf2, nsolver, request, result);
376 template <
typename OrientMeshShapeCollisionTraveralNode,
377 typename BV,
typename Shape,
typename NarrowPhaseSolver>
383 const NarrowPhaseSolver* nsolver,
387 using S =
typename BV::S;
396 OrientMeshShapeCollisionTraveralNode node;
398 const Shape* obj2 =
static_cast<const Shape*
>(o2);
400 initialize(node, *obj1, tf1, *obj2, tf2, nsolver, no_cost_request, result);
412 ShapeShapeCollide<Box<S>, Shape>(&box, box_tf, o2, tf2, nsolver, only_cost_request, result);
416 OrientMeshShapeCollisionTraveralNode node;
418 const Shape* obj2 =
static_cast<const Shape*
>(o2);
420 initialize(node, *obj1, tf1, *obj2, tf2, nsolver, request, result);
428 template <
typename Shape,
typename NarrowPhaseSolver>
430 OBB<typename Shape::
S>, Shape, NarrowPhaseSolver>
432 using S =
typename Shape::S;
439 const NarrowPhaseSolver* nsolver,
448 o1, tf1, o2, tf2, nsolver, request, result);
453 template <
typename Shape,
typename NarrowPhaseSolver>
456 using S =
typename Shape::S;
463 const NarrowPhaseSolver* nsolver,
472 o1, tf1, o2, tf2, nsolver, request, result);
477 template <
typename Shape,
typename NarrowPhaseSolver>
480 using S =
typename Shape::S;
487 const NarrowPhaseSolver* nsolver,
496 o1, tf1, o2, tf2, nsolver, request, result);
501 template <
typename Shape,
typename NarrowPhaseSolver>
504 using S =
typename Shape::S;
511 const NarrowPhaseSolver* nsolver,
520 o1, tf1, o2, tf2, nsolver, request, result);
525 template <
typename S,
typename BV>
546 initialize(node, *obj1_tmp, tf1_tmp, *obj2_tmp, tf2_tmp, request, result);
557 template <
typename BV>
567 o1, tf1, o2, tf2, request, result);
571 template <
typename OrientedMeshCollisionTraversalNode,
typename BV>
582 OrientedMeshCollisionTraversalNode node;
586 initialize(node, *obj1, tf1, *obj2, tf2, request, result);
593 template <
typename S>
606 o1, tf1, o2, tf2, request, result);
611 template <
typename S>
624 o1, tf1, o2, tf2, request, result);
629 template <
typename S>
642 o1, tf1, o2, tf2, request, result);
647 template <
typename BV,
typename NarrowPhaseSolver>
653 const NarrowPhaseSolver* nsolver,
659 return BVHCollide<BV>(o1, tf1, o2, tf2, request, result);
663 template <
typename NarrowPhaseSolver>
666 using S =
typename NarrowPhaseSolver::S;
671 collision_matrix[i][j] =
nullptr;
684 collision_matrix[
GEOM_SPHERE][
GEOM_BOX] = &ShapeShapeCollide<Sphere<S>, Box<S>, NarrowPhaseSolver>;
688 collision_matrix[
GEOM_SPHERE][
GEOM_CONE] = &ShapeShapeCollide<Sphere<S>, Cone<S>, NarrowPhaseSolver>;
691 collision_matrix[
GEOM_SPHERE][
GEOM_PLANE] = &ShapeShapeCollide<Sphere<S>, Plane<S>, NarrowPhaseSolver>;
704 collision_matrix[
GEOM_CAPSULE][
GEOM_BOX] = &ShapeShapeCollide<Capsule<S>, Box<S>, NarrowPhaseSolver>;
708 collision_matrix[
GEOM_CAPSULE][
GEOM_CONE] = &ShapeShapeCollide<Capsule<S>, Cone<S>, NarrowPhaseSolver>;
714 collision_matrix[
GEOM_CONE][
GEOM_BOX] = &ShapeShapeCollide<Cone<S>, Box<S>, NarrowPhaseSolver>;
715 collision_matrix[
GEOM_CONE][
GEOM_SPHERE] = &ShapeShapeCollide<Cone<S>, Sphere<S>, NarrowPhaseSolver>;
717 collision_matrix[
GEOM_CONE][
GEOM_CAPSULE] = &ShapeShapeCollide<Cone<S>, Capsule<S>, NarrowPhaseSolver>;
718 collision_matrix[
GEOM_CONE][
GEOM_CONE] = &ShapeShapeCollide<Cone<S>, Cone<S>, NarrowPhaseSolver>;
720 collision_matrix[
GEOM_CONE][
GEOM_CONVEX] = &ShapeShapeCollide<Cone<S>, Convex<S>, NarrowPhaseSolver>;
721 collision_matrix[
GEOM_CONE][
GEOM_PLANE] = &ShapeShapeCollide<Cone<S>, Plane<S>, NarrowPhaseSolver>;
724 collision_matrix[
GEOM_CYLINDER][
GEOM_BOX] = &ShapeShapeCollide<Cylinder<S>, Box<S>, NarrowPhaseSolver>;
734 collision_matrix[
GEOM_CONVEX][
GEOM_BOX] = &ShapeShapeCollide<Convex<S>, Box<S>, NarrowPhaseSolver>;
738 collision_matrix[
GEOM_CONVEX][
GEOM_CONE] = &ShapeShapeCollide<Convex<S>, Cone<S>, NarrowPhaseSolver>;
741 collision_matrix[
GEOM_CONVEX][
GEOM_PLANE] = &ShapeShapeCollide<Convex<S>, Plane<S>, NarrowPhaseSolver>;
744 collision_matrix[
GEOM_PLANE][
GEOM_BOX] = &ShapeShapeCollide<Plane<S>, Box<S>, NarrowPhaseSolver>;
745 collision_matrix[
GEOM_PLANE][
GEOM_SPHERE] = &ShapeShapeCollide<Plane<S>, Sphere<S>, NarrowPhaseSolver>;
748 collision_matrix[
GEOM_PLANE][
GEOM_CONE] = &ShapeShapeCollide<Plane<S>, Cone<S>, NarrowPhaseSolver>;
750 collision_matrix[
GEOM_PLANE][
GEOM_CONVEX] = &ShapeShapeCollide<Plane<S>, Convex<S>, NarrowPhaseSolver>;
751 collision_matrix[
GEOM_PLANE][
GEOM_PLANE] = &ShapeShapeCollide<Plane<S>, Plane<S>, NarrowPhaseSolver>;
844 collision_matrix[
BV_AABB][
BV_AABB] = &BVHCollide<AABB<S>, NarrowPhaseSolver>;
845 collision_matrix[
BV_OBB][
BV_OBB] = &BVHCollide<OBB<S>, NarrowPhaseSolver>;
846 collision_matrix[
BV_RSS][
BV_RSS] = &BVHCollide<RSS<S>, NarrowPhaseSolver>;
850 collision_matrix[
BV_kIOS][
BV_kIOS] = &BVHCollide<kIOS<S>, NarrowPhaseSolver>;
876 collision_matrix[
GEOM_OCTREE][
BV_AABB] = &OcTreeBVHCollide<AABB<S>, NarrowPhaseSolver>;
877 collision_matrix[
GEOM_OCTREE][
BV_OBB] = &OcTreeBVHCollide<OBB<S>, NarrowPhaseSolver>;
878 collision_matrix[
GEOM_OCTREE][
BV_RSS] = &OcTreeBVHCollide<RSS<S>, NarrowPhaseSolver>;
880 collision_matrix[
GEOM_OCTREE][
BV_kIOS] = &OcTreeBVHCollide<kIOS<S>, NarrowPhaseSolver>;
885 collision_matrix[
BV_AABB][
GEOM_OCTREE] = &BVHOcTreeCollide<AABB<S>, NarrowPhaseSolver>;
886 collision_matrix[
BV_OBB][
GEOM_OCTREE] = &BVHOcTreeCollide<OBB<S>, NarrowPhaseSolver>;
887 collision_matrix[
BV_RSS][
GEOM_OCTREE] = &BVHOcTreeCollide<RSS<S>, NarrowPhaseSolver>;
889 collision_matrix[
BV_kIOS][
GEOM_OCTREE] = &BVHOcTreeCollide<kIOS<S>, NarrowPhaseSolver>;
Vector3< S > cached_gjk_guess
The initial guess to use in the GJK algorithm.
static std::size_t run(const CollisionGeometry< S > *o1, const Transform3< S > &tf1, const CollisionGeometry< S > *o2, const Transform3< S > &tf2, const CollisionRequest< S > &request, CollisionResult< S > &result)
Traversal node for collision between mesh and shape.
size_t numContacts() const
number of contacts found
bool enable_cost
If true, the cost sources will be computed.
Half Space: this is equivalent to the Planed in ODE. The separation plane is defined as n * x = d...
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
std::size_t ShapeShapeCollide(const CollisionGeometry< typename Shape1::S > *o1, const Transform3< typename Shape1::S > &tf1, const CollisionGeometry< typename Shape1::S > *o2, const Transform3< typename Shape1::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape1::S > &request, CollisionResult< typename Shape1::S > &result)
CollisionObject< S > * obj1
CollisionFunctionMatrix()
std::size_t orientedMeshCollide(const CollisionGeometry< typename BV::S > *o1, const Transform3< typename BV::S > &tf1, const CollisionGeometry< typename BV::S > *o2, const Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result)
Center at zero point ellipsoid.
BV::S threshold_free
threshold for free (<= is free)
std::size_t orientedBVHShapeCollide(const CollisionGeometry< typename BV::S > *o1, const Transform3< typename BV::S > &tf1, const CollisionGeometry< typename BV::S > *o2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result)
static std::size_t collide(const CollisionGeometry< S > *o1, const Transform3< S > &tf1, const CollisionGeometry< S > *o2, const Transform3< S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< S > &request, CollisionResult< S > &result)
bool use_approximate_cost
If true, the cost computation is approximated (if computed).
The geometry for the object for collision or distance computation.
typename NarrowPhaseSolver::S S
Vector3< S > cached_gjk_guess
Traversal node for mesh and shape, when mesh BVH is one of the oriented node (OBB, RSS, OBBRSS, kIOS)
Parameters for performing collision request.
template void collide(CollisionTraversalNodeBase< double > *node, BVHFrontList *front_list)
size_t num_max_cost_sources
The maximum number of cost sources that can be returned.
template bool initialize(MeshCollisionTraversalNodeOBB< double > &node, const BVHModel< OBB< double >> &model1, const Transform3< double > &tf1, const BVHModel< OBB< double >> &model2, const Transform3< double > &tf2, const CollisionRequest< double > &request, CollisionResult< double > &result)
Center at zero point, axis aligned box.
bool isSatisfied(const CollisionResult< S > &result) const
static std::size_t run(const CollisionGeometry< S > *o1, const Transform3< S > &tf1, const CollisionGeometry< S > *o2, const Transform3< S > &tf2, const CollisionRequest< S > &request, CollisionResult< S > &result)
BV::S threshold_occupied
threshold for occupied ( >= is occupied)
std::size_t BVHCollide(const CollisionGeometry< typename BV::S > *o1, const Transform3< typename BV::S > &tf1, const CollisionGeometry< typename BV::S > *o2, const Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result)
template void constructBox(const OBB< double > &bv, Box< double > &box, Transform3< double > &tf)
bool enable_cached_gjk_guess
If true, uses the provided initial guess for the GJK algorithm.
Traversal node for collision between two meshes.
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
static std::size_t collide(const CollisionGeometry< S > *o1, const Transform3< S > &tf1, const CollisionGeometry< S > *o2, const Transform3< S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< S > &request, CollisionResult< S > &result)
const BVNode< BV > & getBV(int id) const
We provide getBV() and getNumBVs() because BVH may be compressed (in future), so we must provide some...
static std::size_t collide(const CollisionGeometry< S > *o1, const Transform3< S > &tf1, const CollisionGeometry< S > *o2, const Transform3< S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< S > &request, CollisionResult< S > &result)
BV::S cost_density
collision cost for unit volume
CollisionObject< S > * obj2
Traversal node for collision between two shapes.
Center at zero point sphere.
static std::size_t run(const CollisionGeometry< S > *o1, const Transform3< S > &tf1, const CollisionGeometry< S > *o2, const Transform3< S > &tf2, const CollisionRequest< S > &request, CollisionResult< S > &result)
A class describing the kIOS collision structure, which is a set of spheres.
Traversal node for collision between two meshes if their underlying BVH node is oriented node (OBB...
Oriented bounding box class.