hpp::core::ConfigValidations Class Reference

Validate a configuration with respect to collision. More...

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

Inheritance diagram for hpp::core::ConfigValidations:
[legend]
Collaboration diagram for hpp::core::ConfigValidations:
[legend]

Public Member Functions

virtual bool validate (const Configuration_t &config, ValidationReportPtr_t &validationReport)
 Compute whether the configuration is valid. More...
 
void add (const ConfigValidationPtr_t &configValidation)
 Add a configuration validation object. More...
 
virtual void addObstacle (const CollisionObjectConstPtr_t &object)
 Add an obstacle. More...
 
virtual void removeObstacleFromJoint (const JointPtr_t &joint, const CollisionObjectConstPtr_t &obstacle)
 Remove a collision pair between a joint and an obstacle. More...
 
void filterCollisionPairs (const RelativeMotion::matrix_type &matrix)
 Filter collision pairs. More...
 
size_type numberConfigValidations () const
 Return the number of config validations. More...
 
void clear ()
 
- Public Member Functions inherited from hpp::core::ConfigValidation
virtual ~ConfigValidation ()
 

Static Public Member Functions

static ConfigValidationsPtr_t create ()
 

Protected Member Functions

 ConfigValidations ()
 
- Protected Member Functions inherited from hpp::core::ConfigValidation
 ConfigValidation ()
 

Detailed Description

Validate a configuration with respect to collision.

Constructor & Destructor Documentation

◆ ConfigValidations()

hpp::core::ConfigValidations::ConfigValidations ( )
protected

Member Function Documentation

◆ add()

void hpp::core::ConfigValidations::add ( const ConfigValidationPtr_t configValidation)

Add a configuration validation object.

◆ addObstacle()

virtual void hpp::core::ConfigValidations::addObstacle ( const CollisionObjectConstPtr_t object)
virtual

Add an obstacle.

Parameters
objectobstacle added Store obstacle and build a collision pair with each body of the robot.

Reimplemented from hpp::core::ConfigValidation.

◆ clear()

void hpp::core::ConfigValidations::clear ( )

◆ create()

static ConfigValidationsPtr_t hpp::core::ConfigValidations::create ( )
static

◆ filterCollisionPairs()

void hpp::core::ConfigValidations::filterCollisionPairs ( const RelativeMotion::matrix_type )
virtual

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 from hpp::core::ConfigValidation.

◆ numberConfigValidations()

size_type hpp::core::ConfigValidations::numberConfigValidations ( ) const

Return the number of config validations.

◆ removeObstacleFromJoint()

virtual void hpp::core::ConfigValidations::removeObstacleFromJoint ( const JointPtr_t joint,
const CollisionObjectConstPtr_t obstacle 
)
virtual

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 from hpp::core::ConfigValidation.

◆ validate()

virtual bool hpp::core::ConfigValidations::validate ( const Configuration_t config,
ValidationReportPtr_t validationReport 
)
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.

Implements hpp::core::ConfigValidation.