Struct CollisionRequest

Inheritance Relationships

Base Type

Struct Documentation

struct CollisionRequest : public hpp::fcl::QueryRequest

request to the collision algorithm

Public Functions

inline CollisionRequest(const CollisionRequestFlag flag, size_t num_max_contacts_)

Constructor from a flag and a maximal number of contacts.

Parameters:
  • flag[in] Collision request flag

  • num_max_contacts[in] Maximal number of allowed contacts

inline CollisionRequest()

Default constructor.

bool isSatisfied(const CollisionResult &result) const
inline bool operator==(const CollisionRequest &other) const

whether two CollisionRequest are the same or not

Public Members

size_t num_max_contacts

The maximum number of contacts will return.

bool enable_contact

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

bool enable_distance_lower_bound

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

FCL_REAL security_margin

Distance below which objects are considered in collision. See Collision.

Note

If set to -inf, the objects tested for collision are considered as collision free and no test is actually performed by functions hpp::fcl::collide of class hpp::fcl::ComputeCollision.

FCL_REAL break_distance

Distance below which bounding volumes are broken down. See Collision.

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.

Remark

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