hpp::core::ContinuousValidation Class Referenceabstract

Continuous validation of a path. More...

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

Inheritance diagram for hpp::core::ContinuousValidation:
[legend]
Collaboration diagram for hpp::core::ContinuousValidation:
[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)
 
void changeInitializer (continuousValidation::InitializerPtr_t initializer)
 Change the initializer The continuous validation is then reset and the new initializer is called to do the new initialization. More...
 
value_type tolerance () const
 Get tolerance value. More...
 
virtual ~ContinuousValidation ()
 
- Public Member Functions inherited from hpp::core::PathValidation
virtual ~PathValidation ()
 

Protected Types

typedef continuousValidation::BodyPairCollisions_t BodyPairCollisions_t
 

Protected Member Functions

 ContinuousValidation (const DevicePtr_t &robot, const value_type &tolerance)
 Constructor. More...
 
virtual bool validateConfiguration (BodyPairCollisions_t &bodyPairCollisions, const Configuration_t &config, const value_type &t, interval_t &interval, PathValidationReportPtr_t &report)
 Validate interval centered on a path parameter. More...
 
void init (ContinuousValidationWkPtr_t weak)
 Store weak pointer to itself. More...
 
- Protected Member Functions inherited from hpp::core::PathValidation
 PathValidation ()
 

Static Protected Member Functions

static void setPath (BodyPairCollisions_t &bodyPairCollisions, const PathPtr_t &path, bool reverse)
 

Protected Attributes

DevicePtr_t robot_
 
value_type tolerance_
 
BodyPairCollisions_t bodyPairCollisions_
 
BodyPairCollisions_t disabledBodyPairCollisions_
 
pinocchio::Pool< BodyPairCollisions_tbodyPairCollisionPool_
 
value_type stepSize_
 
continuousValidation::InitializerPtr_t initializer_
 

Detailed Description

Continuous validation of a path.

This class tests for collision

  • straight paths, or
  • concatenation of straight paths (PathVector).

A path is valid if and only if each interval validation element is valid along the whole interval of definition

Interval validation elements can be pairs of objects to test for collision (BodyPairCollision) or an other type of validation.

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

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

Validation of a collision pair 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. This is implemented in BodyPairCollision and SolidSolidCollision.

See this document for details on the continuous collision checking.

See this document for details on the architecture of the code.

Member Typedef Documentation

◆ BodyPairCollisions_t

Constructor & Destructor Documentation

◆ ~ContinuousValidation()

virtual hpp::core::ContinuousValidation::~ContinuousValidation ( )
virtual

◆ ContinuousValidation()

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

Constructor.

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

Member Function Documentation

◆ addObstacle()

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

◆ changeInitializer()

void hpp::core::ContinuousValidation::changeInitializer ( continuousValidation::InitializerPtr_t  initializer)

Change the initializer The continuous validation is then reset and the new initializer is called to do the new initialization.

◆ filterCollisionPairs()

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

Reimplemented from hpp::core::PathValidation.

◆ init()

void hpp::core::ContinuousValidation::init ( ContinuousValidationWkPtr_t  weak)
protected

Store weak pointer to itself.

◆ removeObstacleFromJoint()

virtual void hpp::core::ContinuousValidation::removeObstacleFromJoint ( const JointPtr_t joint,
const CollisionObjectConstPtr_t obstacle 
)
virtual

Remove a collision pair between a joint and an obstacle.

Parameters
jointthe joint that holds the inner objects,
obstaclethe obstacle 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::PathValidation.

◆ setPath()

static void hpp::core::ContinuousValidation::setPath ( BodyPairCollisions_t bodyPairCollisions,
const PathPtr_t path,
bool  reverse 
)
staticprotected

◆ tolerance()

value_type hpp::core::ContinuousValidation::tolerance ( ) const
inline

Get tolerance value.

◆ validate()

virtual bool hpp::core::ContinuousValidation::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
validPartthe extracted 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
true if the whole path is valid.

Implements hpp::core::PathValidation.

◆ validateConfiguration()

virtual bool hpp::core::ContinuousValidation::validateConfiguration ( BodyPairCollisions_t bodyPairCollisions,
const Configuration_t config,
const value_type t,
interval_t interval,
PathValidationReportPtr_t report 
)
protectedvirtual

Validate interval centered on a path parameter.

Parameters
bodyPairCollisionscollision to consider
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

◆ bodyPairCollisionPool_

pinocchio::Pool<BodyPairCollisions_t> hpp::core::ContinuousValidation::bodyPairCollisionPool_
protected

◆ bodyPairCollisions_

BodyPairCollisions_t hpp::core::ContinuousValidation::bodyPairCollisions_
protected

◆ disabledBodyPairCollisions_

BodyPairCollisions_t hpp::core::ContinuousValidation::disabledBodyPairCollisions_
protected

◆ initializer_

continuousValidation::InitializerPtr_t hpp::core::ContinuousValidation::initializer_
protected

◆ robot_

DevicePtr_t hpp::core::ContinuousValidation::robot_
protected

◆ stepSize_

value_type hpp::core::ContinuousValidation::stepSize_
protected

◆ tolerance_

value_type hpp::core::ContinuousValidation::tolerance_
protected