hpp-fcl
1.8.0
HPP fork of FCL -- The Flexible Collision Library
|
request to the collision algorithm More...
#include <hpp/fcl/collision_data.h>
Public Member Functions | |
CollisionRequest (const CollisionRequestFlag flag, size_t num_max_contacts_) | |
Constructor from a flag and a maximal number of contacts. More... | |
CollisionRequest () | |
Default constructor. More... | |
bool | isSatisfied (const CollisionResult &result) const |
bool | operator== (const CollisionRequest &other) const |
whether two CollisionRequest are the same or not More... | |
![]() | |
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... | |
![]() | |
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... | |
request to the collision algorithm
|
inline |
Constructor from a flag and a maximal number of contacts.
[in] | flag | Collision request flag |
[in] | num_max_contacts | Maximal number of allowad contacts |
|
inline |
Default constructor.
bool hpp::fcl::CollisionRequest::isSatisfied | ( | const CollisionResult & | result | ) | const |
|
inline |
whether two CollisionRequest are the same or not
FCL_REAL hpp::fcl::CollisionRequest::break_distance |
Distance below which bounding volumes are broken down. See Collision detection and distance lower 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.
bool hpp::fcl::CollisionRequest::enable_contact |
whether the contact information (normal, penetration depth and contact position) will return
bool hpp::fcl::CollisionRequest::enable_distance_lower_bound |
Whether a lower bound on distance is returned when objects are disjoint.
size_t hpp::fcl::CollisionRequest::num_max_contacts |
The maximum number of contacts will return.
FCL_REAL hpp::fcl::CollisionRequest::security_margin |
Distance below which objects are considered in collision. See Collision detection and distance lower bound.