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:
Collaboration diagram for hpp::core::ConfigValidations:

List of all members.

Public Member Functions

virtual bool validate (const Configuration_t &config, bool throwIfInValid=false)
 Compute whether the configuration is valid.
virtual bool validate (const Configuration_t &config, ValidationReport &validationReport, bool throwIfInValid=false)
 Compute whether the configuration is valid.
void add (const ConfigValidationPtr_t &configValidation)
 Add a configuration validation object.
virtual void addObstacle (const CollisionObjectPtr_t &object)
 Add an obstacle.
virtual void removeObstacleFromJoint (const JointPtr_t &joint, const CollisionObjectPtr_t &obstacle)
 Remove a collision pair between a joint and an obstacle.

Static Public Member Functions

static ConfigValidationsPtr_t create ()

Protected Member Functions

 ConfigValidations ()

Detailed Description

Validate a configuration with respect to collision.


Constructor & Destructor Documentation

hpp::core::ConfigValidations::ConfigValidations ( ) [protected]

Member Function Documentation

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

Add a configuration validation object.

virtual void hpp::core::ConfigValidations::addObstacle ( const CollisionObjectPtr_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.

static ConfigValidationsPtr_t hpp::core::ConfigValidations::create ( ) [static]
virtual void hpp::core::ConfigValidations::removeObstacleFromJoint ( const JointPtr_t joint,
const CollisionObjectPtr_t obstacle 
) [virtual]

Remove a collision pair between a joint and an obstacle.

Parameters:
thejoint that holds the inner objects,
theobstacle to remove. 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.

virtual bool hpp::core::ConfigValidations::validate ( const Configuration_t config,
bool  throwIfInValid = false 
) [virtual]

Compute whether the configuration is valid.

Parameters:
configthe config to check for validity,
throwIfInValidif true throw an exception if config is invalid.
Returns:
whether the whole config is valid.

Implements hpp::core::ConfigValidation.

virtual bool hpp::core::ConfigValidations::validate ( const Configuration_t config,
ValidationReport validationReport,
bool  throwIfInValid = false 
) [virtual]

Compute whether the configuration is valid.

Parameters:
configthe config to check for validity,
throwIfInValidif true throw an exception if config is invalid.
Return values:
validationReportreport on validation
Returns:
whether the whole config is valid.

Implements hpp::core::ConfigValidation.