request to the distance computation More...
#include <distance_request.h>
Public Member Functions | |
DistanceRequest (bool enable_nearest_points_=false, bool enable_signed_distance=false, S rel_err_=0.0, S abs_err_=0.0, S distance_tolerance=1e-6, GJKSolverType gjk_solver_type_=GST_LIBCCD) | |
bool | isSatisfied (const DistanceResult< S > &result) const |
Public Attributes | |
S | abs_err |
S | distance_tolerance |
the threshold used in GJK algorithm to stop distance iteration More... | |
bool | enable_nearest_points |
whether to return the nearest points More... | |
bool | enable_signed_distance |
Whether to compute exact negative distance. More... | |
GJKSolverType | gjk_solver_type |
narrow phase solver type More... | |
S | rel_err |
error threshold for approximate distance More... | |
request to the distance computation
Definition at line 52 of file distance_request.h.
|
explicit |
Definition at line 54 of file distance_request-inl.h.
bool fcl::DistanceRequest< S >::isSatisfied | ( | const DistanceResult< S > & | result | ) | const |
Definition at line 73 of file distance_request-inl.h.
S fcl::DistanceRequest< S >::abs_err |
Definition at line 96 of file distance_request.h.
S fcl::DistanceRequest< S >::distance_tolerance |
the threshold used in GJK algorithm to stop distance iteration
Definition at line 99 of file distance_request.h.
bool fcl::DistanceRequest< S >::enable_nearest_points |
whether to return the nearest points
Definition at line 55 of file distance_request.h.
bool fcl::DistanceRequest< S >::enable_signed_distance |
Whether to compute exact negative distance.
Basically, the distance computation routine computes only the exact positive distance when the two objects are not in collision. If the objects are in collision, the result distance is implementation defined (mostly -1).
[ Current Implementation Status ]
--------------—+-----------—+-----------— GJKSolverType | GST_LIBCCD | GST_INDEP --------------—+-----------—+-----------— primitive shapes | SD_1, NP | SD_2, NP_X mesh and octree | SD_2, NP_X | SD_2, NP_X --------------—+-----------—+-----------— SD_1: Signed distance is computed using convexity based methods (GJK, MPA) SD_2: Positive distance is computed using convexity based mothods (GJK, MPA), but negative distance is computed by a workaround using penetration computation. NP : The pair of nearest points are guaranteed to be on the surface of objects. NP_X: The pair of nearest points are NOT guaranteed to be on the surface of objects.
If this flag is set to true, FCL will perform additional collision checking when the two objects are in collision in order to get the exact negative distance, which is the negated penetration depth. If there are multiple contact for the two objects, then the maximum penetration depth is used.
If this flag is set to false, the result minimum distance is implementation defined (mostly -1).
The default is false.
Definition at line 92 of file distance_request.h.
GJKSolverType fcl::DistanceRequest< S >::gjk_solver_type |
narrow phase solver type
Definition at line 102 of file distance_request.h.
S fcl::DistanceRequest< S >::rel_err |
error threshold for approximate distance
Definition at line 95 of file distance_request.h.