Validate a configuration with respect to collision. More...
#include <hpp/core/collision-validation.hh>
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 |
![]() | |
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) | |
![]() | |
ConfigValidation () | |
Protected Attributes | |
DevicePtr_t | robot_ |
CollisionPairs_t | collisionPairs_ |
CollisionPairs_t | parameterizedPairs_ |
CollisionPairs_t | disabledPairs_ |
Validate a configuration with respect to collision.
|
protected |
|
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.
|
virtual |
Add an obstacle to a specific joint.
object | obstacle added |
joint | concerned with obstacle addition |
includeChildren | whether to add obstacle to joint children Store obstacle and build a collision pair with each body of the robot. |
|
inline |
|
inline |
|
inline |
|
static |
|
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.
square | symmetric matrix of RelativeMotionType of size numberDof x numberDof |
Reimplemented from hpp::core::ConfigValidation.
|
virtual |
Remove a collision pair between a joint and an obstacle.
the | joint that holds the inner objects, |
the | obstacle to remove. |
Reimplemented from hpp::core::ConfigValidation.
|
virtual |
Compute whether the configuration is valid.
config | the config to check for validity, |
validationReport | report on validation. If non valid, a validation report will be allocated and returned via this shared pointer. |
Implements hpp::core::ConfigValidation.
|
protected |
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.
|
protected |
|
protected |
|
protected |