hpp::core::CollisionValidation Class Reference

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

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

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

Public Member Functions

virtual bool validate (const Configuration_t &config, ValidationReportPtr_t &validationReport)
 Compute whether the configuration is valid. More...
 
virtual void addObstacle (const CollisionObjectConstPtr_t &object)
 Add an obstacle. More...
 
virtual void addObstacleToJoint (const CollisionObjectConstPtr_t &object, const JointPtr_t &joint, const bool includeChildren)
 Add an obstacle to a specific joint. 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...
 
void checkParameterized (bool active)
 
void computeAllContacts (bool computeAllContacts)
 
bool checkParameterized () const
 
- Public Member Functions inherited from hpp::core::ConfigValidation
virtual ~ConfigValidation ()
 

Static Public Member Functions

static CollisionValidationPtr_t create (const DevicePtr_t &robot)
 

Public Attributes

fcl::CollisionRequest collisionRequest_
 fcl low level request object used for collision checking. More...
 

Protected Member Functions

 CollisionValidation (const DevicePtr_t &robot)
 
- Protected Member Functions inherited from hpp::core::ConfigValidation
 ConfigValidation ()
 

Protected Attributes

DevicePtr_t robot_
 
CollisionPairs_t collisionPairs_
 
CollisionPairs_t parameterizedPairs_
 
CollisionPairs_t disabledPairs_
 

Detailed Description

Validate a configuration with respect to collision.

Constructor & Destructor Documentation

◆ CollisionValidation()

hpp::core::CollisionValidation::CollisionValidation ( const DevicePtr_t robot)
protected

Member Function Documentation

◆ addObstacle()

virtual void hpp::core::CollisionValidation::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.

◆ addObstacleToJoint()

virtual void hpp::core::CollisionValidation::addObstacleToJoint ( const CollisionObjectConstPtr_t object,
const JointPtr_t joint,
const bool  includeChildren 
)
virtual

Add an obstacle to a specific joint.

Parameters
objectobstacle added
jointconcerned with obstacle addition
includeChildrenwhether to add obstacle to joint children Store obstacle and build a collision pair with each body of the robot.

◆ checkParameterized() [1/2]

void hpp::core::CollisionValidation::checkParameterized ( bool  active)
inline

◆ checkParameterized() [2/2]

bool hpp::core::CollisionValidation::checkParameterized ( ) const
inline

◆ computeAllContacts()

void hpp::core::CollisionValidation::computeAllContacts ( bool  computeAllContacts)
inline

◆ create()

static CollisionValidationPtr_t hpp::core::CollisionValidation::create ( const DevicePtr_t robot)
static

◆ filterCollisionPairs()

void hpp::core::CollisionValidation::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.

◆ removeObstacleFromJoint()

virtual void hpp::core::CollisionValidation::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::CollisionValidation::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.

Member Data Documentation

◆ collisionPairs_

CollisionPairs_t hpp::core::CollisionValidation::collisionPairs_
protected

◆ collisionRequest_

fcl::CollisionRequest hpp::core::CollisionValidation::collisionRequest_

fcl low level request object used for collision checking.

modify this attribute to obtain more detailed validation reports in a call to validate.

◆ disabledPairs_

CollisionPairs_t hpp::core::CollisionValidation::disabledPairs_
protected

◆ parameterizedPairs_

CollisionPairs_t hpp::core::CollisionValidation::parameterizedPairs_
protected

◆ robot_

DevicePtr_t hpp::core::CollisionValidation::robot_
protected