38 #ifndef FCL_DISTANCE_INL_H 39 #define FCL_DISTANCE_INL_H 53 const DistanceRequest<double>& request,
54 DistanceResult<double>& result);
61 const DistanceRequest<double>& request, DistanceResult<double>& result);
64 template <
typename GJKSolver>
72 template <
typename NarrowPhaseSolver>
76 const NarrowPhaseSolver* nsolver,
80 return distance<NarrowPhaseSolver>(
91 template <
typename NarrowPhaseSolver>
97 const NarrowPhaseSolver* nsolver_,
101 using S =
typename NarrowPhaseSolver::S;
103 const NarrowPhaseSolver* nsolver = nsolver_;
105 nsolver =
new NarrowPhaseSolver();
107 const auto& looktable = getDistanceFunctionLookTable<NarrowPhaseSolver>();
119 if(!looktable.distance_matrix[node_type2][node_type1])
121 std::cerr <<
"Warning: distance function between node type " << node_type1 <<
" and node type " << node_type2 <<
" is not supported\n";
125 res = looktable.distance_matrix[node_type2][node_type1](o2, tf2, o1, tf1, nsolver, request, result);
130 if(!looktable.distance_matrix[node_type1][node_type2])
132 std::cerr <<
"Warning: distance function between node type " << node_type1 <<
" and node type " << node_type2 <<
" is not supported\n";
136 res = looktable.distance_matrix[node_type1][node_type2](o1, tf1, o2, tf2, nsolver, request, result);
162 collide(o1, tf1, o2, tf2, nsolver, collision_request, collision_result);
165 std::size_t index =
static_cast<std::size_t
>(-1);
167 for (
auto i = 0u; i < collision_result.
numContacts(); ++i)
169 const auto& contact = collision_result.
getContact(i);
170 if (max_pen_depth < contact.penetration_depth)
172 max_pen_depth = contact.penetration_depth;
177 assert(index != static_cast<std::size_t>(-1));
196 template <
typename S>
209 return distance(o1, o2, &solver, request, result);
215 return distance(o1, o2, &solver, request, result);
223 template <
typename S>
235 return distance(o1, tf1, o2, tf2, &solver, request, result);
241 return distance(o1, tf1, o2, tf2, &solver, request, result);
size_t numContacts() const
number of contacts found
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
S min_distance
Minimum distance between two objects.
virtual NODE_TYPE getNodeType() const
get the node type
virtual OBJECT_TYPE getObjectType() const
get the type of the object
distance matrix stores the functions for distance between different types of objects and provides a u...
template class FCL_EXPORT CollisionGeometry< double >
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
const Contact< S > & getContact(size_t i) const
get the i-th contact calculated
S gjk_tolerance
the threshold used in GJK to stop iteration
S distance(const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2, Vector3< S > *P, Vector3< S > *Q)
Approximate distance between two kIOS bounding volumes.
Eigen::Matrix< S, 3, 1 > Vector3
The geometry for the object for collision or distance computation.
detail::DistanceFunctionMatrix< GJKSolver > & getDistanceFunctionLookTable()
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)
bool enable_contact
If true, contact information (e.g., normal, penetration depth, and contact position) will be returned...
S distance_tolerance
the threshold used in GJK algorithm to stop distance iteration
Parameters for performing collision request.
bool enable_nearest_points
whether to return the nearest points
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
GJKSolverType gjk_solver_type
narrow phase solver type
the object for collision or distance computation, contains the geometry and the transform information...
bool enable_signed_distance
Whether to compute exact negative distance.
template class FCL_EXPORT CollisionObject< double >
collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the ...
S distance_tolerance
the threshold used in GJK algorithm to stop distance iteration
bool isCollision() const
return binary collision result
Vector3< S > nearest_points[2]
Nearest points in the world coordinates.
request to the distance computation
const std::shared_ptr< const CollisionGeometry< S > > & collisionGeometry() const
get geometry from the object instance