38 #ifndef FCL_COLLISION_INL_H 39 #define FCL_COLLISION_INL_H 56 const CollisionRequest<double>& request,
57 CollisionResult<double>& result);
64 const Transform3<double>& tf1,
66 const Transform3<double>& tf2,
67 const CollisionRequest<double>& request,
68 CollisionResult<double>& result);
71 template<
typename GJKSolver>
79 template <
typename S,
typename NarrowPhaseSolver>
84 const NarrowPhaseSolver* nsolver,
89 nsolver, request, result);
93 template <
typename S,
typename NarrowPhaseSolver>
100 const NarrowPhaseSolver* nsolver_,
104 const NarrowPhaseSolver* nsolver = nsolver_;
106 nsolver =
new NarrowPhaseSolver();
108 const auto& looktable = getCollisionFunctionLookTable<NarrowPhaseSolver>();
113 std::cerr <<
"Warning: should stop early as num_max_contact is " << request.
num_max_contacts <<
" !\n";
125 if(!looktable.collision_matrix[node_type2][node_type1])
127 std::cerr <<
"Warning: collision function between node type " << node_type1 <<
" and node type " << node_type2 <<
" is not supported\n";
131 res = looktable.collision_matrix[node_type2][node_type1](o2, tf2, o1, tf1, nsolver, request, result);
135 if(!looktable.collision_matrix[node_type1][node_type2])
137 std::cerr <<
"Warning: collision function between node type " << node_type1 <<
" and node type " << node_type2 <<
" is not supported\n";
141 res = looktable.collision_matrix[node_type1][node_type2](o1, tf1, o2, tf2, nsolver, request, result);
152 template <
typename S>
163 return collide(o1, o2, &solver, request, result);
170 return collide(o1, o2, &solver, request, result);
178 template <
typename S>
194 return collide(o1, tf1, o2, tf2, &solver, request, result);
201 return collide(o1, tf1, o2, tf2, &solver, request, result);
204 std::cerr <<
"Warning! Invalid GJK solver\n";
const Transform3< S > & getTransform() const
get object's transform
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18, kDOP24), basic shape (box, sphere, ellipsoid, capsule, cone, cylinder, convex, plane, halfspace, triangle), and octree
virtual NODE_TYPE getNodeType() const
get the node type
size_t num_max_contacts
The maximum number of contacts that can be returned.
virtual OBJECT_TYPE getObjectType() const
get the type of the object
detail::CollisionFunctionMatrix< GJKSolver > & getCollisionFunctionLookTable()
template class FCL_EXPORT CollisionGeometry< double >
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
S gjk_tolerance
the threshold used in GJK to stop iteration
S collision_tolerance
the threshold used in GJK algorithm to stop collision iteration
The geometry for the object for collision or distance computation.
GJKSolverType gjk_solver_type
Enumeration indicating the GJK solver implementation to use.
collision and distance solver based on libccd library.
template FCL_EXPORT std::size_t collide(const CollisionObject< double > *o1, const CollisionObject< double > *o2, const CollisionRequest< double > &request, CollisionResult< double > &result)
Real gjk_tolerance
Numerical tolerance to use in the GJK algorithm. NOTE: The default value is currently set as 1e-6 to ...
Parameters for performing collision request.
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
the object for collision or distance computation, contains the geometry and the transform information...
template class FCL_EXPORT CollisionObject< double >
collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the ...
collision matrix stores the functions for collision between different types of objects and provides a...
S epa_tolerance
the threshold used in EPA to stop iteration
const std::shared_ptr< const CollisionGeometry< S > > & collisionGeometry() const
get geometry from the object instance