hpp-core  4.9.0
Implement basic classes for canonical path planning for kinematic chains.
hpp::core::ContinuousValidation Class Referenceabstract

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

Inheritance diagram for hpp::core::ContinuousValidation:
Collaboration diagram for hpp::core::ContinuousValidation:

Classes

class  AddObstacle
 
class  Initialize
 

Public Member Functions

virtual bool validate (const PathPtr_t &path, bool reverse, PathPtr_t &validPart, PathValidationReportPtr_t &report)
 
virtual void addObstacle (const CollisionObjectConstPtr_t &object)
 
virtual void removeObstacleFromJoint (const JointPtr_t &joint, const CollisionObjectConstPtr_t &obstacle)
 
void filterCollisionPairs (const RelativeMotion::matrix_type &relMotion)
 
virtual void setSecurityMargins (const matrix_t &securityMatrix)
 
void addIntervalValidation (const IntervalValidationPtr_t &intervalValidation)
 
value_type tolerance () const
 Get tolerance value. More...
 
DevicePtr_t robot () const
 
void initialize ()
 
virtual ~ContinuousValidation ()
 
Delegate
template<class Delegate >
void add (const Delegate &delegate)
 
template<class Delegate >
void reset ()
 
- Public Member Functions inherited from hpp::core::PathValidation
virtual ~PathValidation ()
 
- Public Member Functions inherited from hpp::core::ObstacleUserInterface
virtual ~ObstacleUserInterface ()
 

Protected Types

typedef continuousValidation::IntervalValidations_t IntervalValidations_t
 

Protected Member Functions

 ContinuousValidation (const DevicePtr_t &robot, const value_type &tolerance)
 
virtual bool validateConfiguration (IntervalValidations_t &intervalValidations, const Configuration_t &config, const value_type &t, interval_t &interval, PathValidationReportPtr_t &report)
 
bool validateIntervals (IntervalValidations_t &validations, const value_type &t, interval_t &interval, PathValidationReportPtr_t &pathReport, typename IntervalValidations_t::iterator &smallestInterval, pinocchio::DeviceData &data)
 
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 (IntervalValidations_t &intervalValidations, const PathPtr_t &path, bool reverse)
 

Protected Attributes

DevicePtr_t robot_
 
value_type tolerance_
 
IntervalValidations_t intervalValidations_
 All BodyPairValidation to validate. More...
 
IntervalValidations_t disabledBodyPairCollisions_
 BodyPairCollision for which collision is disabled. More...
 
pinocchio::Pool< IntervalValidations_tbodyPairCollisionPool_
 
value_type stepSize_
 

Detailed Description

Continuous validation of a path

This class valides a path for various criteria. The default validation criterion is the absence of collisions between bodies of a robot and the environment.

Validation of PathVector instances is performed path by path.

A path is valid if and only if each interval validation element is valid along the whole interval of definition (class continuousValidation::IntervalValidation).

In order to validate other criteria, users can add their own derivation of class continuousValidation::IntervalValidation using method addIntervalValidation. They can also make use of two types of delegates:

Base class ContinuousValidation::Initialize initializes collision pairs between bodies of the robot.

Validation of a collision pair 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 continuousValidation::BodyPairCollision and continuousValidation::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

◆ IntervalValidations_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

◆ add()

template<class Delegate >
void hpp::core::ContinuousValidation::add ( const Delegate &  delegate)

Add a delegate

Template Parameters
Delegatetype of delegate.
Parameters
instanceof delegate class.

Delegates are used to enable users to specialize some actions of the class without deriving the class. This class supports two types of delegates:

◆ addIntervalValidation()

void hpp::core::ContinuousValidation::addIntervalValidation ( const IntervalValidationPtr_t &  intervalValidation)

Add interval validation instance

◆ addObstacle()

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

Iteratively call method doExecute of delegate classes AddObstacle

Parameters
objectnew obstacle.
See also
ContinuousValidation::add, ContinuousValidation::AddObstacle.

Implements hpp::core::ObstacleUserInterface.

◆ filterCollisionPairs()

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

Filter collision pairs.

Remove pairs of object that cannot be in collision. This effectively disables collision detection between objects that have no possible relative motion due to the constraints.

Parameters
relMotionsquare symmetric matrix of RelativeMotionType of size numberDof x numberDof

Implements hpp::core::ObstacleUserInterface.

◆ init()

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

Store weak pointer to itself.

◆ initialize()

void hpp::core::ContinuousValidation::initialize ( )

Iteratively call method doExecute of delegate classes Initialize

See also
ContinuousValidation::add, ContinuousValidation::Initialize.

◆ 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.

Implements hpp::core::ObstacleUserInterface.

◆ reset()

template<class Delegate >
void hpp::core::ContinuousValidation::reset ( )

Reset delegates of a type

Template Parameters
delegatetype of delegate

◆ robot()

DevicePtr_t hpp::core::ContinuousValidation::robot ( ) const
inline

◆ setPath()

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

◆ setSecurityMargins()

virtual void hpp::core::ContinuousValidation::setSecurityMargins ( const matrix_t securityMatrix)
virtual

Set different security margins for collision pairs

This method enables users to choose different security margins for each pair of robot body or each pair robot body - obstacle.

See also
hpp::fcl::CollisionRequest::security_margin.

Implements hpp::core::ObstacleUserInterface.

◆ 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 ( IntervalValidations_t intervalValidations,
const Configuration_t config,
const value_type t,
interval_t interval,
PathValidationReportPtr_t report 
)
protectedvirtual

Validate interval centered on a path parameter

Parameters
intervalValidationscollision 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.

◆ validateIntervals()

bool hpp::core::ContinuousValidation::validateIntervals ( IntervalValidations_t validations,
const value_type t,
interval_t interval,
PathValidationReportPtr_t pathReport,
typename IntervalValidations_t::iterator &  smallestInterval,
pinocchio::DeviceData data 
)
inlineprotected

Validate a set of intervals for a given parameter along a path

Template Parameters
IntervalValidationtype of container of validation elements (for instance validation for collision between a pair of bodies),
ValidationReportTypePtr_ttype of validation report produced in case non validation. Should derive from ValidationReport.
Parameters
objectsable to validate an interval for collision,
tcenter of the interval to be validated,
Return values
intervalinterval validated for all objects,
smallestIntervaliterator to the validation element that returned the smallest interval.

Member Data Documentation

◆ bodyPairCollisionPool_

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

◆ disabledBodyPairCollisions_

IntervalValidations_t hpp::core::ContinuousValidation::disabledBodyPairCollisions_
protected

BodyPairCollision for which collision is disabled.

◆ intervalValidations_

IntervalValidations_t hpp::core::ContinuousValidation::intervalValidations_
protected

All BodyPairValidation to validate.

◆ robot_

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

◆ stepSize_

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

◆ tolerance_

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

The documentation for this class was generated from the following file: