request to the distance computation More...
#include <hpp/fcl/collision_data.h>
Public Member Functions | |
DistanceRequest (bool enable_nearest_points_=false, FCL_REAL rel_err_=0.0, FCL_REAL abs_err_=0.0, GJKSolverType gjk_solver_type_=GST_LIBCCD) | |
bool | isSatisfied (const DistanceResult &result) const |
Public Attributes | |
bool | enable_nearest_points |
whether to return the nearest points | |
FCL_REAL | rel_err |
error threshold for approximate distance | |
FCL_REAL | abs_err |
GJKSolverType | gjk_solver_type |
narrow phase solver type |
request to the distance computation
fcl::DistanceRequest::DistanceRequest | ( | bool | enable_nearest_points_ = false , |
FCL_REAL | rel_err_ = 0.0 , |
||
FCL_REAL | abs_err_ = 0.0 , |
||
GJKSolverType | gjk_solver_type_ = GST_LIBCCD |
||
) | [inline] |
bool fcl::DistanceRequest::isSatisfied | ( | const DistanceResult & | result | ) | const |
whether to return the nearest points
Referenced by fcl::MeshDistanceTraversalNode< OBBRSS >::leafTesting().
narrow phase solver type
error threshold for approximate distance
Referenced by fcl::MeshDistanceTraversalNode< OBBRSS >::MeshDistanceTraversalNode().