Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
hpp::core::ContinuousCollisionChecking Class Referenceabstract

Continuous validation of a path for collision. More...

#include <hpp/core/continuous-collision-checking.hh>

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

Public Member Functions

virtual bool validate (const PathPtr_t &path, bool reverse, PathPtr_t &validPart, PathValidationReportPtr_t &report)
 Compute the largest valid interval starting from the path beginning. 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 &relMotion)
 
virtual ~ContinuousCollisionChecking ()
 
- Public Member Functions inherited from hpp::core::PathValidation
virtual ~PathValidation ()
 

Protected Member Functions

 ContinuousCollisionChecking (const DevicePtr_t &robot, const value_type &tolerance)
 Constructor. More...
 
bool validateConfiguration (const Configuration_t &config, const value_type &t, interval_t &interval, PathValidationReportPtr_t &report)
 Validate interval centered on a path parameter. More...
 
- Protected Member Functions inherited from hpp::core::PathValidation
 PathValidation ()
 

Protected Attributes

DevicePtr_t robot_
 
value_type tolerance_
 
continuousCollisionChecking::BodyPairCollisions_t bodyPairCollisions_
 
continuousCollisionChecking::BodyPairCollisions_t disabledBodyPairCollisions_
 
value_type stepSize_
 

Detailed Description

Continuous validation of a path for collision.

This class is derived into two sub-classes that test for collision

A path is valid if and only if each pair of objects to test is collision-free along the whole interval of definition.

Collision pairs between bodies of the robot are initialized at construction of the instance.

Method addObstacle adds an obstacle in the environment. For each joint, a new pair is created with the new obstacle.

Validation of pairs along straight interpolations is based on the computation of an upper-bound of the relative velocity of objects of one joint (or of the environment) in the reference frame of the other joint.

See this document for details.

Constructor & Destructor Documentation

◆ ~ContinuousCollisionChecking()

virtual hpp::core::ContinuousCollisionChecking::~ContinuousCollisionChecking ( )
virtual

◆ ContinuousCollisionChecking()

hpp::core::ContinuousCollisionChecking::ContinuousCollisionChecking ( const DevicePtr_t robot,
const value_type tolerance 
)
protected

Constructor.

Parameters
robotthe robot for which collision checking is performed,
tolerancemaximal penetration allowed.

Member Function Documentation

◆ addObstacle()

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

Add an obstacle.

Parameters
objectobstacle added Add the object to each collision pair a body of which is the environment. care about obstacles.

Reimplemented from hpp::core::PathValidation.

◆ filterCollisionPairs()

void hpp::core::ContinuousCollisionChecking::filterCollisionPairs ( const RelativeMotion::matrix_type relMotion)
virtual

Reimplemented from hpp::core::PathValidation.

◆ removeObstacleFromJoint()

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

◆ validate()

virtual bool hpp::core::ContinuousCollisionChecking::validate ( const PathPtr_t path,
bool  reverse,
PathPtr_t validPart,
PathValidationReportPtr_t report 
)
virtual

Compute the largest valid interval starting from the path beginning.

Parameters
paththe path to check for validity,
reverseif true check from the end,
Return values
theextracted valid part of the path, pointer to path if path is valid.
reportinformation about the validation process. A report is allocated if the path is not valid.
Returns
whether the whole path is valid.

Implements hpp::core::PathValidation.

◆ validateConfiguration()

bool hpp::core::ContinuousCollisionChecking::validateConfiguration ( const Configuration_t config,
const value_type t,
interval_t interval,
PathValidationReportPtr_t report 
)
protected

Validate interval centered on a path parameter.

Parameters
configConfiguration at abscissa t on the path.
tparameter value in the path interval of definition
Return values
intervalinterval over which the path is collision-free, not necessarily included in definition interval
Returns
true if the body pair is collision free for this parameter value, false if the body pair is in collision.
Note
object should be in the positions defined by the configuration of parameter t on the path.

Member Data Documentation

◆ bodyPairCollisions_

continuousCollisionChecking::BodyPairCollisions_t hpp::core::ContinuousCollisionChecking::bodyPairCollisions_
protected

◆ disabledBodyPairCollisions_

continuousCollisionChecking::BodyPairCollisions_t hpp::core::ContinuousCollisionChecking::disabledBodyPairCollisions_
protected

◆ robot_

DevicePtr_t hpp::core::ContinuousCollisionChecking::robot_
protected

◆ stepSize_

value_type hpp::core::ContinuousCollisionChecking::stepSize_
protected

◆ tolerance_

value_type hpp::core::ContinuousCollisionChecking::tolerance_
protected