Public Member Functions | Public Attributes | List of all members
hpp::fcl::DistanceRequest Struct Reference

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_INDEP)
 
bool isSatisfied (const DistanceResult &result) const
 

Public Attributes

bool enable_nearest_points
 whether to return the nearest points More...
 
FCL_REAL rel_err
 error threshold for approximate distance More...
 
FCL_REAL abs_err
 
GJKSolverType gjk_solver_type
 narrow phase solver type More...
 

Detailed Description

request to the distance computation

Constructor & Destructor Documentation

hpp::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_INDEP 
)
inline

Member Function Documentation

bool hpp::fcl::DistanceRequest::isSatisfied ( const DistanceResult result) const

Member Data Documentation

FCL_REAL hpp::fcl::DistanceRequest::abs_err
bool hpp::fcl::DistanceRequest::enable_nearest_points

whether to return the nearest points

GJKSolverType hpp::fcl::DistanceRequest::gjk_solver_type

narrow phase solver type

FCL_REAL hpp::fcl::DistanceRequest::rel_err

error threshold for approximate distance