Abstraction of configuration validation. More...
#include <hpp/core/config-validation.hh>
Public Member Functions | |
virtual bool | validate (const Configuration_t &config, ValidationReportPtr_t &validationReport)=0 |
Compute whether the configuration is valid. More... | |
virtual void | addObstacle (const CollisionObjectConstPtr_t &) |
Add an obstacle. More... | |
virtual void | removeObstacleFromJoint (const JointPtr_t &, const CollisionObjectConstPtr_t &) |
Remove a collision pair between a joint and an obstacle. More... | |
virtual void | filterCollisionPairs (const RelativeMotion::matrix_type &) |
Filter collision pairs. More... | |
virtual | ~ConfigValidation () |
Protected Member Functions | |
ConfigValidation () | |
Abstraction of configuration validation.
Instances of this class validate configurations with respect to some criteria
|
inlinevirtual |
|
inlineprotected |
|
inlinevirtual |
Add an obstacle.
object | obstacle added |
Reimplemented in hpp::core::CollisionValidation, and hpp::core::ConfigValidations.
|
inlinevirtual |
Filter collision pairs.
Remove pairs of object that cannot be in collision when these constraints are statisfied. This effectively disables collision detection between objects that have no possible relative motion due to the constraints.
square | symmetric matrix of RelativeMotionType of size numberDof x numberDof |
Reimplemented in hpp::core::CollisionValidation, and hpp::core::ConfigValidations.
|
inlinevirtual |
Remove a collision pair between a joint and an obstacle.
the | joint that holds the inner objects, |
the | obstacle to remove. |
Reimplemented in hpp::core::CollisionValidation, and hpp::core::ConfigValidations.
|
pure 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. |
Implemented in hpp::core::JointBoundValidation, hpp::core::CollisionValidation, and hpp::core::ConfigValidations.