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

request to the distance computation More...

#include <collision_data.h>

Inheritance diagram for hpp::fcl::DistanceRequest:
Inheritance graph
[legend]

Public Member Functions

 DistanceRequest (bool enable_nearest_points_=false, FCL_REAL rel_err_=0.0, FCL_REAL abs_err_=0.0)
 
bool isSatisfied (const DistanceResult &result) const
 
bool operator== (const DistanceRequest &other) const
 whether two DistanceRequest are the same or not More...
 
- Public Member Functions inherited from hpp::fcl::QueryRequest
QueryRequestoperator= (const QueryRequest &other)=default
 Copy assignment operator. More...
 
bool operator== (const QueryRequest &other) const
 whether two QueryRequest are the same or not More...
 
HPP_FCL_COMPILER_DIAGNOSTIC_PUSH HPP_FCL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS QueryRequest ()
 Default constructor. More...
 
 QueryRequest (const QueryRequest &other)=default
 Copy constructor. More...
 
HPP_FCL_COMPILER_DIAGNOSTIC_POP void updateGuess (const QueryResult &result)
 

Public Attributes

FCL_REAL abs_err
 
bool enable_nearest_points
 whether to return the nearest points More...
 
FCL_REAL rel_err
 error threshold for approximate distance More...
 
- Public Attributes inherited from hpp::fcl::QueryRequest
Vec3f cached_gjk_guess
 the gjk initial guess set by user More...
 
support_func_guess_t cached_support_func_guess
 the support function initial guess set by user More...
 
FCL_REAL collision_distance_threshold
 threshold below which a collision is considered. More...
 
bool enable_cached_gjk_guess
 whether enable gjk initial guess @Deprecated Use gjk_initial_guess instead More...
 
bool enable_timings
 enable timings when performing collision/distance request More...
 
GJKConvergenceCriterion gjk_convergence_criterion
 convergence criterion used to stop GJK More...
 
GJKConvergenceCriterionType gjk_convergence_criterion_type
 convergence criterion used to stop GJK More...
 
GJKInitialGuess gjk_initial_guess
 
size_t gjk_max_iterations
 maximum iteration for the GJK algorithm More...
 
FCL_REAL gjk_tolerance
 tolerance for the GJK algorithm More...
 
GJKVariant gjk_variant
 whether to enable the Nesterov accleration of GJK More...
 

Detailed Description

request to the distance computation

Definition at line 392 of file collision_data.h.

Constructor & Destructor Documentation

◆ DistanceRequest()

hpp::fcl::DistanceRequest::DistanceRequest ( bool  enable_nearest_points_ = false,
FCL_REAL  rel_err_ = 0.0,
FCL_REAL  abs_err_ = 0.0 
)
inline
Parameters
enable_nearest_points_enables the nearest points computation.
rel_err_
abs_err_

Definition at line 403 of file collision_data.h.

Member Function Documentation

◆ isSatisfied()

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

Definition at line 47 of file collision_data.cpp.

◆ operator==()

bool hpp::fcl::DistanceRequest::operator== ( const DistanceRequest other) const
inline

whether two DistanceRequest are the same or not

Definition at line 412 of file collision_data.h.

Member Data Documentation

◆ abs_err

FCL_REAL hpp::fcl::DistanceRequest::abs_err

Definition at line 398 of file collision_data.h.

◆ enable_nearest_points

bool hpp::fcl::DistanceRequest::enable_nearest_points

whether to return the nearest points

Definition at line 394 of file collision_data.h.

◆ rel_err

FCL_REAL hpp::fcl::DistanceRequest::rel_err

error threshold for approximate distance

Definition at line 397 of file collision_data.h.


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


hpp-fcl
Author(s):
autogenerated on Fri Mar 8 2024 03:46:34