Public Member Functions | Public Attributes | List of all members
fcl::DistanceRequest< S > Struct Template Reference

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

abs_err
 
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...
 
rel_err
 error threshold for approximate distance More...
 

Detailed Description

template<typename S>
struct fcl::DistanceRequest< S >

request to the distance computation

Definition at line 52 of file distance_request.h.

Constructor & Destructor Documentation

◆ DistanceRequest()

template<typename S >
fcl::DistanceRequest< S >::DistanceRequest ( bool  enable_nearest_points_ = false,
bool  enable_signed_distance = false,
rel_err_ = 0.0,
abs_err_ = 0.0,
distance_tolerance = 1e-6,
GJKSolverType  gjk_solver_type_ = GST_LIBCCD 
)
explicit

Definition at line 54 of file distance_request-inl.h.

Member Function Documentation

◆ isSatisfied()

template<typename S >
bool fcl::DistanceRequest< S >::isSatisfied ( const DistanceResult< S > &  result) const

Definition at line 73 of file distance_request-inl.h.

Member Data Documentation

◆ abs_err

template<typename S >
S fcl::DistanceRequest< S >::abs_err

Definition at line 96 of file distance_request.h.

◆ distance_tolerance

template<typename S >
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.

◆ enable_nearest_points

template<typename S >
bool fcl::DistanceRequest< S >::enable_nearest_points

whether to return the nearest points

Definition at line 55 of file distance_request.h.

◆ enable_signed_distance

template<typename S >
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.

See also
DistanceResult::min_distance

Definition at line 92 of file distance_request.h.

◆ gjk_solver_type

template<typename S >
GJKSolverType fcl::DistanceRequest< S >::gjk_solver_type

narrow phase solver type

Definition at line 102 of file distance_request.h.

◆ rel_err

template<typename S >
S fcl::DistanceRequest< S >::rel_err

error threshold for approximate distance

Definition at line 95 of file distance_request.h.


The documentation for this struct was generated from the following files:


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:50