hpp::core::continuousValidation::BodyPairCollision Class Referenceabstract

Computation of collision-free sub-intervals of a path. More...

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

Inheritance diagram for hpp::core::continuousValidation::BodyPairCollision:
[legend]
Collaboration diagram for hpp::core::continuousValidation::BodyPairCollision:
[legend]

Public Types

typedef std::pair< CollisionObjectConstPtr_t, CollisionObjectConstPtr_tCollisionPair_t
 
typedef std::vector< CollisionPair_tCollisionPairs_t
 

Public Member Functions

bool validateConfiguration (const value_type &t, interval_t &interval, CollisionValidationReportPtr_t &report, pinocchio::DeviceData &data)
 Validate interval centered on a path parameter. More...
 
const CollisionPairs_tpairs () const
 
CollisionPairs_tpairs ()
 
value_type maximalVelocity () const
 
virtual size_type indexJointA () const
 Returns joint A index or -1 if no such joint exists. More...
 
virtual size_type indexJointB () const
 Returns joint B index or -1 if no such joint exists. More...
 
virtual bool removeObjectTo_b (const CollisionObjectConstPtr_t &)
 
virtual void addCollisionPair (const CollisionObjectConstPtr_t &, const CollisionObjectConstPtr_t &)
 
virtual std::string name () const =0
 
virtual std::ostream & print (std::ostream &os) const =0
 
virtual BodyPairCollisionPtr_t copy () const =0
 
- Public Member Functions inherited from hpp::core::continuousValidation::IntervalValidation< CollisionValidationReportPtr_t >
void path (const PathPtr_t &path, bool reverse)
 Set path to validate. More...
 
PathConstPtr_t path () const
 Get path. More...
 
value_type tolerance () const
 

Protected Member Functions

 BodyPairCollision (value_type tolerance)
 Constructor of body pair collision. More...
 
 BodyPairCollision (const BodyPairCollision &other)
 Copy constructor. More...
 
virtual void setReport (CollisionValidationReportPtr_t &report, fcl::CollisionResult result, CollisionPair_t _pair) const
 
- Protected Member Functions inherited from hpp::core::continuousValidation::IntervalValidation< CollisionValidationReportPtr_t >
 IntervalValidation (value_type tolerance)
 Constructor of interval validation element. More...
 
 IntervalValidation (const IntervalValidation &other)
 

Additional Inherited Members

- Protected Types inherited from hpp::core::continuousValidation::IntervalValidation< CollisionValidationReportPtr_t >
typedef boost::icl::continuous_interval< value_typecontinuous_interval
 
typedef boost::icl::interval_set< value_typeinterval_set
 
- Protected Attributes inherited from hpp::core::continuousValidation::IntervalValidation< CollisionValidationReportPtr_t >
PathPtr_t path_
 
value_type tolerance_
 
bool reverse_
 
bool refine_
 
bool valid_
 
interval_set validInterval_
 

Detailed Description

Computation of collision-free sub-intervals of a path.

This class aims at validating a path for the absence of collision between two bodies of a robot, which are in most common cases two solid bodies (see SolidSolidCollision). With this abstraction, other bodies (like cables) can also be checked for collision.

The interval of definition of the path is successively covered by intervals where boths bodies are proved to be collision-free. Each interval is computed by bounding from above the velocity of all points of body 1 in the reference frame of body 2.

See this document for details.

Member Typedef Documentation

◆ CollisionPair_t

◆ CollisionPairs_t

Constructor & Destructor Documentation

◆ BodyPairCollision() [1/2]

hpp::core::continuousValidation::BodyPairCollision::BodyPairCollision ( value_type  tolerance)
inlineprotected

Constructor of body pair collision.

Parameters
toleranceallowed penetration should be positive

◆ BodyPairCollision() [2/2]

hpp::core::continuousValidation::BodyPairCollision::BodyPairCollision ( const BodyPairCollision other)
inlineprotected

Copy constructor.

Member Function Documentation

◆ addCollisionPair()

virtual void hpp::core::continuousValidation::BodyPairCollision::addCollisionPair ( const CollisionObjectConstPtr_t ,
const CollisionObjectConstPtr_t  
)
inlinevirtual

◆ copy()

virtual BodyPairCollisionPtr_t hpp::core::continuousValidation::BodyPairCollision::copy ( ) const
pure virtual

◆ indexJointA()

virtual size_type hpp::core::continuousValidation::BodyPairCollision::indexJointA ( ) const
inlinevirtual

Returns joint A index or -1 if no such joint exists.

Reimplemented in hpp::core::continuousValidation::SolidSolidCollision.

◆ indexJointB()

virtual size_type hpp::core::continuousValidation::BodyPairCollision::indexJointB ( ) const
inlinevirtual

Returns joint B index or -1 if no such joint exists.

Reimplemented in hpp::core::continuousValidation::SolidSolidCollision.

◆ maximalVelocity()

value_type hpp::core::continuousValidation::BodyPairCollision::maximalVelocity ( ) const
inline

◆ name()

virtual std::string hpp::core::continuousValidation::BodyPairCollision::name ( ) const
pure virtual

◆ pairs() [1/2]

const CollisionPairs_t& hpp::core::continuousValidation::BodyPairCollision::pairs ( ) const
inline

Referenced by setReport().

◆ pairs() [2/2]

CollisionPairs_t& hpp::core::continuousValidation::BodyPairCollision::pairs ( )
inline

◆ print()

virtual std::ostream& hpp::core::continuousValidation::BodyPairCollision::print ( std::ostream &  os) const
pure virtual

◆ removeObjectTo_b()

virtual bool hpp::core::continuousValidation::BodyPairCollision::removeObjectTo_b ( const CollisionObjectConstPtr_t )
inlinevirtual

◆ setReport()

virtual void hpp::core::continuousValidation::BodyPairCollision::setReport ( CollisionValidationReportPtr_t report,
fcl::CollisionResult  result,
CollisionPair_t  _pair 
) const
inlineprotectedvirtual

References pairs().

◆ validateConfiguration()

bool hpp::core::continuousValidation::BodyPairCollision::validateConfiguration ( const value_type t,
interval_t interval,
CollisionValidationReportPtr_t report,
pinocchio::DeviceData &  data 
)
virtual

Validate interval centered on a path parameter.

Parameters
tparameter value in the path interval of definition
[in,out]intervalas input, interval over which collision checking must be performed. As output, interval over which pair is collision-free, not necessarily included in definition interval.
reportthe collision validation report
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.

Implements hpp::core::continuousValidation::IntervalValidation< CollisionValidationReportPtr_t >.