|
hpp-core
6.0.0
Implement basic classes for canonical path planning for kinematic chains.
|
#include <hpp/core/collision-validation.hh>


Public Member Functions | |
| virtual bool | validate (const Configuration_t &config, ValidationReportPtr_t &validationReport) |
| void | checkParameterized (bool active) |
| void | computeAllContacts (bool computeAllContacts) |
| bool | checkParameterized () const |
Public Member Functions inherited from hpp::core::ConfigValidation | |
| virtual | ~ConfigValidation ()=default |
Public Member Functions inherited from hpp::core::ObstacleUser | |
| virtual | ~ObstacleUser ()=default |
| const CollisionPairs_t & | pairs () const |
| CollisionPairs_t & | pairs () |
| const CollisionRequests_t & | requests () const |
| CollisionRequests_t & | requests () |
| coal::CollisionRequest & | defaultRequest () |
| void | setRequests (const coal::CollisionRequest &r) |
| virtual void | addObstacle (const CollisionObjectConstPtr_t &object) |
| virtual void | addObstacleToJoint (const CollisionObjectConstPtr_t &object, const JointPtr_t &joint, const bool includeChildren) |
| virtual void | removeObstacleFromJoint (const JointPtr_t &joint, const CollisionObjectConstPtr_t &object) |
| virtual void | filterCollisionPairs (const RelativeMotion::matrix_type &relMotion) |
| virtual void | setSecurityMargins (const matrix_t &securityMatrix) |
| virtual void | setSecurityMarginBetweenBodies (const std::string &body_a, const std::string &body_b, const value_type &margin) |
Public Member Functions inherited from hpp::core::ObstacleUserInterface | |
| virtual | ~ObstacleUserInterface ()=default |
Static Public Member Functions | |
| static CollisionValidationPtr_t | create (const DevicePtr_t &robot) |
Static Public Member Functions inherited from hpp::core::ObstacleUser | |
| static bool | collide (const CollisionPairs_t &pairs, CollisionRequests_t &reqs, coal::CollisionResult &res, std::size_t &i, pinocchio::DeviceData &data) |
Protected Member Functions | |
| CollisionValidation (const DevicePtr_t &robot) | |
Protected Member Functions inherited from hpp::core::ConfigValidation | |
| ConfigValidation ()=default | |
Protected Member Functions inherited from hpp::core::ObstacleUser | |
| ObstacleUser (DevicePtr_t robot) | |
| Constructor of body pair collision. More... | |
| ObstacleUser (const ObstacleUser &other) | |
| Copy constructor. More... | |
| void | addRobotCollisionPairs () |
Protected Attributes | |
| DevicePtr_t | robot_ |
Protected Attributes inherited from hpp::core::ObstacleUser | |
| DevicePtr_t | robot_ |
| coal::CollisionRequest | defaultRequest_ |
| CollisionPairs_t | cPairs_ |
| CollisionPairs_t | pPairs_ |
| Active collision pairs. More... | |
| CollisionPairs_t | dPairs_ |
| Parameterized collision pairs. More... | |
| CollisionRequests_t | cRequests_ |
| Disabled collision pairs. More... | |
| CollisionRequests_t | pRequests_ |
| Active collision requests. More... | |
| CollisionRequests_t | dRequests_ |
| Parameterized collision requests. More... | |
Validate a configuration with respect to collision
|
protected |
|
inline |
|
inline |
|
inline |
|
static |
|
virtual |
Compute whether the configuration is valid
| config | the config to check for validity, |
| validationReport | report on validation. If non valid, a validation report will be allocated and returned via this shared pointer. |
Implements hpp::core::ConfigValidation.
|
protected |