|
coal 3.0.1
Coal, The Collision Detection Library. Previously known as HPP-FCL, fork of FCL -- The Flexible Collision Library
|
request to the distance computation More...
#include <coal/collision_data.h>


Public Member Functions | |
| DistanceRequest (bool enable_nearest_points_=true, bool enable_signed_distance_=true, Scalar rel_err_=0.0, Scalar 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 | |
Public Member Functions inherited from coal::QueryRequest | |
| QueryRequest () | |
| Default constructor. | |
| QueryRequest (const QueryRequest &other)=default | |
| Copy constructor. | |
| QueryRequest & | operator= (const QueryRequest &other)=default |
| Copy assignment operator. | |
| 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. | |
| bool | operator== (const QueryRequest &other) const |
| whether two QueryRequest are the same or not | |
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. | |
| 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. | |
| Scalar | rel_err |
| error threshold for approximate distance | |
| Scalar | abs_err |
Public Attributes inherited from coal::QueryRequest | |
| GJKInitialGuess | gjk_initial_guess |
| bool | enable_cached_gjk_guess |
| whether enable gjk initial guess @Deprecated Use gjk_initial_guess instead | |
| Vec3s | cached_gjk_guess |
| the gjk initial guess set by user | |
| support_func_guess_t | cached_support_func_guess |
| the support function initial guess set by user | |
| size_t | gjk_max_iterations |
| maximum iteration for the GJK algorithm | |
| Scalar | 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. | |
| GJKVariant | gjk_variant |
| whether to enable the Nesterov accleration of GJK | |
| GJKConvergenceCriterion | gjk_convergence_criterion |
| convergence criterion used to stop GJK | |
| GJKConvergenceCriterionType | gjk_convergence_criterion_type |
| convergence criterion used to stop GJK | |
| size_t | epa_max_iterations |
| max number of iterations for EPA | |
| Scalar | 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. | |
| bool | enable_timings |
| enable timings when performing collision/distance request | |
| Scalar | collision_distance_threshold |
| threshold below which a collision is considered. | |
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 coal::DistanceRequest::isSatisfied | ( | const DistanceResult & | result | ) | const |
|
default |
|
inline |
whether two DistanceRequest are the same or not
| Scalar coal::DistanceRequest::abs_err |
| bool coal::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 coal::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. | Scalar coal::DistanceRequest::rel_err |
error threshold for approximate distance