hpp::core::continuousValidation::SolidSolidCollision Class Reference

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

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

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

Public Member Functions

value_type computeMaximalVelocity (vector_t &Vb) const
 Compute maximal velocity for a given velocity bound. More...
 
bool removeObjectTo_b (const CollisionObjectConstPtr_t &object)
 
std::string name () const
 
std::ostream & print (std::ostream &os) const
 
void addCollisionPair (const CollisionObjectConstPtr_t &left, const CollisionObjectConstPtr_t &right)
 
const CoefficientVelocities_tcoefficients () const
 
const JointPtr_tjoint_a () const
 Get joint a. More...
 
const JointPtr_tjoint_b () const
 Get joint b. More...
 
size_type indexJointA () const
 Returns joint A index or -1 if no such joint exists. More...
 
size_type indexJointB () const
 Returns joint B index or -1 if no such joint exists. More...
 
BodyPairCollisionPtr_t copy () const
 
- Public Member Functions inherited from hpp::core::continuousValidation::BodyPairCollision
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
 
- 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
 

Static Public Member Functions

static SolidSolidCollisionPtr_t create (const JointPtr_t &joint_a, const ConstObjectStdVector_t &objects_b, value_type tolerance)
 Create instance and return shared pointer. More...
 
static SolidSolidCollisionPtr_t create (const JointPtr_t &joint_a, const JointPtr_t &joint_b, value_type tolerance)
 Create instance and return shared pointer. More...
 

Protected Member Functions

 SolidSolidCollision (const JointPtr_t &joint_a, const JointPtr_t &joint_b, value_type tolerance)
 Constructor of inter-body collision checking. More...
 
 SolidSolidCollision (const JointPtr_t &joint_a, const ConstObjectStdVector_t &objects_b, value_type tolerance)
 Constructor of collision checking with the environment. More...
 
 SolidSolidCollision (const SolidSolidCollision &other)
 
- Protected Member Functions inherited from hpp::core::continuousValidation::BodyPairCollision
 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

- Public Types inherited from hpp::core::continuousValidation::BodyPairCollision
typedef std::pair< CollisionObjectConstPtr_t, CollisionObjectConstPtr_tCollisionPair_t
 
typedef std::vector< CollisionPair_tCollisionPairs_t
 
- 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 solid bodies of a robot.

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.

Constructor & Destructor Documentation

◆ SolidSolidCollision() [1/3]

hpp::core::continuousValidation::SolidSolidCollision::SolidSolidCollision ( const JointPtr_t joint_a,
const JointPtr_t joint_b,
value_type  tolerance 
)
protected

Constructor of inter-body collision checking.

Parameters
joint_a,joint_bjoint of the bodies to test for collision
toleranceallowed penetration should be positive
Precondition
joint_a and joint_b should not be nul pointers.

◆ SolidSolidCollision() [2/3]

hpp::core::continuousValidation::SolidSolidCollision::SolidSolidCollision ( const JointPtr_t joint_a,
const ConstObjectStdVector_t objects_b,
value_type  tolerance 
)
protected

Constructor of collision checking with the environment.

Parameters
joint_ajoint of the body to test for collision with the environment
objects_benvironment objects for the collision checking
toleranceallowed penetration should be positive
Precondition
objects_b should not be attached to a joint

◆ SolidSolidCollision() [3/3]

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

Member Function Documentation

◆ addCollisionPair()

void hpp::core::continuousValidation::SolidSolidCollision::addCollisionPair ( const CollisionObjectConstPtr_t left,
const CollisionObjectConstPtr_t right 
)
virtual
Note
The left object should belong to joint_a and the right one should belong to joint_b, or vice-versa. This is not checked.

Reimplemented from hpp::core::continuousValidation::BodyPairCollision.

◆ coefficients()

const CoefficientVelocities_t& hpp::core::continuousValidation::SolidSolidCollision::coefficients ( ) const
inline

◆ computeMaximalVelocity()

value_type hpp::core::continuousValidation::SolidSolidCollision::computeMaximalVelocity ( vector_t Vb) const
virtual

Compute maximal velocity for a given velocity bound.

Parameters
Vbvelocity

Implements hpp::core::continuousValidation::BodyPairCollision.

◆ copy()

BodyPairCollisionPtr_t hpp::core::continuousValidation::SolidSolidCollision::copy ( ) const
virtual

◆ create() [1/2]

static SolidSolidCollisionPtr_t hpp::core::continuousValidation::SolidSolidCollision::create ( const JointPtr_t joint_a,
const ConstObjectStdVector_t objects_b,
value_type  tolerance 
)
static

Create instance and return shared pointer.

Parameters
joint_ajoint of the body to test for collision with the environment
objects_benvironment objects for the collision checking
toleranceallowed penetration should be positive
Precondition
objects_b should not be attached to a joint

◆ create() [2/2]

static SolidSolidCollisionPtr_t hpp::core::continuousValidation::SolidSolidCollision::create ( const JointPtr_t joint_a,
const JointPtr_t joint_b,
value_type  tolerance 
)
static

Create instance and return shared pointer.

Parameters
joint_a,joint_bjoint of the bodies to test for collision
toleranceallowed penetrationd be positive

◆ indexJointA()

size_type hpp::core::continuousValidation::SolidSolidCollision::indexJointA ( ) const
inlinevirtual

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

Reimplemented from hpp::core::continuousValidation::BodyPairCollision.

◆ indexJointB()

size_type hpp::core::continuousValidation::SolidSolidCollision::indexJointB ( ) const
inlinevirtual

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

Reimplemented from hpp::core::continuousValidation::BodyPairCollision.

◆ joint_a()

const JointPtr_t& hpp::core::continuousValidation::SolidSolidCollision::joint_a ( ) const
inline

Get joint a.

◆ joint_b()

const JointPtr_t& hpp::core::continuousValidation::SolidSolidCollision::joint_b ( ) const
inline

Get joint b.

◆ name()

std::string hpp::core::continuousValidation::SolidSolidCollision::name ( ) const
virtual

◆ print()

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

◆ removeObjectTo_b()

bool hpp::core::continuousValidation::SolidSolidCollision::removeObjectTo_b ( const CollisionObjectConstPtr_t object)
virtual