|
hpp-fcl
3.0.0
HPP fork of FCL -- The Flexible Collision Library
|
request to the distance computation More...
#include <hpp/fcl/collision_data.h>


Public Member Functions | |
| DistanceRequest (bool enable_nearest_points_=true, bool enable_signed_distance_=true, FCL_REAL rel_err_=0.0, FCL_REAL abs_err_=0.0) | |
| bool | isSatisfied (const DistanceResult &result) const |
| DistanceRequest & | operator= (const DistanceRequest &other)=default |
| bool | operator== (const DistanceRequest &other) const |
| whether two DistanceRequest are the same or not More... | |
Public Member Functions inherited from hpp::fcl::QueryRequest | |
| QueryRequest () | |
| Default constructor. More... | |
| QueryRequest (const QueryRequest &other)=default | |
| Copy constructor. More... | |
| QueryRequest & | operator= (const QueryRequest &other)=default |
| Copy assignment operator. More... | |
| void | updateGuess (const QueryResult &result) const |
| Updates the guess for the internal GJK algorithm in order to warm-start it when reusing this collision request on the same collision pair. More... | |
| bool | operator== (const QueryRequest &other) const |
| whether two QueryRequest are the same or not More... | |
Public Attributes | |
| bool | enable_nearest_points |
whether to return the nearest points. Nearest points are always computed and are the points of the shapes that achieve a distance of DistanceResult::min_distance. More... | |
| bool | enable_signed_distance |
| whether to compute the penetration depth when objects are in collision. Turning this off can save computation time if only the distance when objects are disjoint is needed. More... | |
| FCL_REAL | rel_err |
| error threshold for approximate distance More... | |
| FCL_REAL | abs_err |
Public Attributes inherited from hpp::fcl::QueryRequest | |
| GJKInitialGuess | gjk_initial_guess |
| bool | enable_cached_gjk_guess |
| whether enable gjk initial guess @Deprecated Use gjk_initial_guess instead More... | |
| 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... | |
| size_t | gjk_max_iterations |
| maximum iteration for the GJK algorithm More... | |
| FCL_REAL | gjk_tolerance |
| tolerance for the GJK algorithm. Note: This tolerance determines the precision on the estimated distance between two geometries which are not in collision. It is recommended to not set this tolerance to less than 1e-6. More... | |
| GJKVariant | gjk_variant |
| whether to enable the Nesterov accleration of GJK More... | |
| GJKConvergenceCriterion | gjk_convergence_criterion |
| convergence criterion used to stop GJK More... | |
| GJKConvergenceCriterionType | gjk_convergence_criterion_type |
| convergence criterion used to stop GJK More... | |
| size_t | epa_max_iterations |
| max number of iterations for EPA More... | |
| FCL_REAL | epa_tolerance |
| tolerance for EPA. Note: This tolerance determines the precision on the estimated distance between two geometries which are in collision. It is recommended to not set this tolerance to less than 1e-6. Also, setting EPA's tolerance to less than GJK's is not recommended. More... | |
| bool | enable_timings |
| enable timings when performing collision/distance request More... | |
| FCL_REAL | collision_distance_threshold |
| threshold below which a collision is considered. More... | |
request to the distance computation
|
inline |
| enable_nearest_points_ | enables the nearest points computation. |
| enable_signed_distance_ | allows to compute the penetration depth |
| rel_err_ | |
| abs_err_ |
| bool hpp::fcl::DistanceRequest::isSatisfied | ( | const DistanceResult & | result | ) | const |
|
default |
|
inline |
whether two DistanceRequest are the same or not
| FCL_REAL hpp::fcl::DistanceRequest::abs_err |
| bool hpp::fcl::DistanceRequest::enable_nearest_points |
whether to return the nearest points. Nearest points are always computed and are the points of the shapes that achieve a distance of DistanceResult::min_distance.
| bool hpp::fcl::DistanceRequest::enable_signed_distance |
whether to compute the penetration depth when objects are in collision. Turning this off can save computation time if only the distance when objects are disjoint is needed.
DistanceResult::min_distance. If enable_signed_distance is off, DistanceResult::min_distance is always positive. If enable_signed_distance is on, DistanceResult::min_distance can be positive or negative. The nearest points are the points of the shapes that achieve a distance of DistanceResult::min_distance. | FCL_REAL hpp::fcl::DistanceRequest::rel_err |
error threshold for approximate distance