hpp-fcl  1.7.4
HPP fork of FCL -- The Flexible Collision Library
hpp::fcl::CollisionRequest Struct Reference

request to the collision algorithm More...

#include <hpp/fcl/collision_data.h>

Inheritance diagram for hpp::fcl::CollisionRequest:
Collaboration diagram for hpp::fcl::CollisionRequest:

Public Member Functions

 CollisionRequest (const CollisionRequestFlag flag, size_t num_max_contacts_)
 
 CollisionRequest ()
 
bool isSatisfied (const CollisionResult &result) const
 
bool operator== (const CollisionRequest &other) const
 whether two CollisionRequest are the same or not More...
 
- Public Member Functions inherited from hpp::fcl::QueryRequest
 QueryRequest ()
 
void updateGuess (const QueryResult &result)
 
bool operator== (const QueryRequest &other) const
 whether two QueryRequest are the same or not More...
 

Public Attributes

size_t num_max_contacts
 The maximum number of contacts will return. More...
 
bool enable_contact
 whether the contact information (normal, penetration depth and contact position) will return More...
 
bool enable_distance_lower_bound
 Whether a lower bound on distance is returned when objects are disjoint. More...
 
FCL_REAL security_margin
 Distance below which objects are considered in collision. See Collision detection and distance lower bound. More...
 
FCL_REAL break_distance
 Distance below which bounding volumes are broken down. See Collision detection and distance lower bound. More...
 
FCL_REAL distance_upper_bound
 Distance above which GJK solver makes an early stopping. GJK stops searching for the closest points when it proves that the distance between two geometries is above this threshold. More...
 
- Public Attributes inherited from hpp::fcl::QueryRequest
bool enable_cached_gjk_guess
 whether enable gjk intial guess More...
 
Vec3f cached_gjk_guess
 the gjk intial guess set by user More...
 
support_func_guess_t cached_support_func_guess
 the support function intial guess set by user More...
 
bool enable_timings
 enable timings when performing collision/distance request More...
 

Detailed Description

request to the collision algorithm

Constructor & Destructor Documentation

◆ CollisionRequest() [1/2]

hpp::fcl::CollisionRequest::CollisionRequest ( const CollisionRequestFlag  flag,
size_t  num_max_contacts_ 
)
inlineexplicit

◆ CollisionRequest() [2/2]

hpp::fcl::CollisionRequest::CollisionRequest ( )
inline

Member Function Documentation

◆ isSatisfied()

bool hpp::fcl::CollisionRequest::isSatisfied ( const CollisionResult result) const

◆ operator==()

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

whether two CollisionRequest are the same or not

Member Data Documentation

◆ break_distance

FCL_REAL hpp::fcl::CollisionRequest::break_distance

Distance below which bounding volumes are broken down. See Collision detection and distance lower bound.

◆ distance_upper_bound

FCL_REAL hpp::fcl::CollisionRequest::distance_upper_bound

Distance above which GJK solver makes an early stopping. GJK stops searching for the closest points when it proves that the distance between two geometries is above this threshold.

Remarks
Consequently, the closest points might be incorrect, but allows to save computational ressources.

◆ enable_contact

bool hpp::fcl::CollisionRequest::enable_contact

whether the contact information (normal, penetration depth and contact position) will return

◆ enable_distance_lower_bound

bool hpp::fcl::CollisionRequest::enable_distance_lower_bound

Whether a lower bound on distance is returned when objects are disjoint.

◆ num_max_contacts

size_t hpp::fcl::CollisionRequest::num_max_contacts

The maximum number of contacts will return.

◆ security_margin

FCL_REAL hpp::fcl::CollisionRequest::security_margin

Distance below which objects are considered in collision. See Collision detection and distance lower bound.


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