hpp-fcl  1.4.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>

Public Member Functions

 CollisionRequest (size_t num_max_contacts_, bool enable_contact_=false, bool enable_distance_lower_bound_=false, size_t num_max_cost_sources_=1, bool enable_cost_=false, bool use_approximate_cost_=true) HPP_FCL_DEPRECATED
 
 CollisionRequest (const CollisionRequestFlag flag, size_t num_max_contacts_)
 
 CollisionRequest ()
 
bool isSatisfied (const CollisionResult &result) const
 

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...
 
bool enable_cached_gjk_guess
 whether enable gjk intial guess More...
 
Vec3f cached_gjk_guess
 the gjk intial guess set by user 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...
 

Detailed Description

request to the collision algorithm

Constructor & Destructor Documentation

◆ CollisionRequest() [1/3]

hpp::fcl::CollisionRequest::CollisionRequest ( size_t  num_max_contacts_,
bool  enable_contact_ = false,
bool  enable_distance_lower_bound_ = false,
size_t  num_max_cost_sources_ = 1,
bool  enable_cost_ = false,
bool  use_approximate_cost_ = true 
)
explicit

◆ CollisionRequest() [2/3]

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

◆ CollisionRequest() [3/3]

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

Member Function Documentation

◆ isSatisfied()

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

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.

◆ cached_gjk_guess

Vec3f hpp::fcl::CollisionRequest::cached_gjk_guess

the gjk intial guess set by user

◆ enable_cached_gjk_guess

bool hpp::fcl::CollisionRequest::enable_cached_gjk_guess

whether enable gjk intial guess

◆ 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: