hpp::core::ConfigValidation Class Referenceabstract

Abstraction of configuration validation. More...

#include <hpp/core/config-validation.hh>

Inheritance diagram for hpp::core::ConfigValidation:
[legend]

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 ()
 

Detailed Description

Abstraction of configuration validation.

Instances of this class validate configurations with respect to some criteria

Constructor & Destructor Documentation

◆ ~ConfigValidation()

virtual hpp::core::ConfigValidation::~ConfigValidation ( )
inlinevirtual

◆ ConfigValidation()

hpp::core::ConfigValidation::ConfigValidation ( )
inlineprotected

Member Function Documentation

◆ addObstacle()

virtual void hpp::core::ConfigValidation::addObstacle ( const CollisionObjectConstPtr_t )
inlinevirtual

Add an obstacle.

Parameters
objectobstacle added
Note
collision configuration validation needs to know about obstacles. This virtual method does nothing for configuration validation methods that do not care about obstacles.

Reimplemented in hpp::core::CollisionValidation, and hpp::core::ConfigValidations.

◆ filterCollisionPairs()

virtual void hpp::core::ConfigValidation::filterCollisionPairs ( const RelativeMotion::matrix_type )
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.

Todo:
Before disabling collision pair, check if there is a collision.
Parameters
squaresymmetric matrix of RelativeMotionType of size numberDof x numberDof

Reimplemented in hpp::core::CollisionValidation, and hpp::core::ConfigValidations.

◆ removeObstacleFromJoint()

virtual void hpp::core::ConfigValidation::removeObstacleFromJoint ( const JointPtr_t ,
const CollisionObjectConstPtr_t  
)
inlinevirtual

Remove a collision pair between a joint and an obstacle.

Parameters
thejoint that holds the inner objects,
theobstacle to remove.
Note
collision configuration validation needs to know about obstacles. This virtual method does nothing for configuration validation methods that do not care about obstacles.

Reimplemented in hpp::core::CollisionValidation, and hpp::core::ConfigValidations.

◆ validate()

virtual bool hpp::core::ConfigValidation::validate ( const Configuration_t config,
ValidationReportPtr_t validationReport 
)
pure virtual

Compute whether the configuration is valid.

Parameters
configthe config to check for validity,
Return values
validationReportreport on validation. If non valid, a validation report will be allocated and returned via this shared pointer.
Returns
whether the whole config is valid.

Implemented in hpp::core::JointBoundValidation, hpp::core::CollisionValidation, and hpp::core::ConfigValidations.