Validate a configuration with respect to collision. More...
#include <hpp/core/collision-validation.hh>
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. | |
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 CollisionValidationPtr_t | create (const DevicePtr_t &robot) |
Protected Member Functions | |
CollisionValidation (const DevicePtr_t &robot) |
Validate a configuration with respect to collision.
hpp::core::CollisionValidation::CollisionValidation | ( | const DevicePtr_t & | robot | ) | [protected] |
virtual void hpp::core::CollisionValidation::addObstacle | ( | const CollisionObjectPtr_t & | object | ) | [virtual] |
Add an obstacle.
object | obstacle added Store obstacle and build a collision pair with each body of the robot. |
Reimplemented from hpp::core::ConfigValidation.
static CollisionValidationPtr_t hpp::core::CollisionValidation::create | ( | const DevicePtr_t & | robot | ) | [static] |
virtual void hpp::core::CollisionValidation::removeObstacleFromJoint | ( | const JointPtr_t & | joint, |
const CollisionObjectPtr_t & | obstacle | ||
) | [virtual] |
Remove a collision pair between a joint and an obstacle.
the | joint that holds the inner objects, |
the | obstacle 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::CollisionValidation::validate | ( | const Configuration_t & | config, |
bool | throwIfInValid = false |
||
) | [virtual] |
Compute whether the configuration is valid.
config | the config to check for validity, |
throwIfInValid | if true throw an exception if config is invalid. |
Implements hpp::core::ConfigValidation.
virtual bool hpp::core::CollisionValidation::validate | ( | const Configuration_t & | config, |
ValidationReport & | validationReport, | ||
bool | throwIfInValid = false |
||
) | [virtual] |
Compute whether the configuration is valid.
config | the config to check for validity, |
validationReport | report on validation. This parameter will dynamically cast into CollisionValidationReport type, |
throwIfInValid | if true throw an exception if config is invalid, |
Implements hpp::core::ConfigValidation.