hpp-core
4.9.0
Implement basic classes for canonical path planning for kinematic chains.
|
#include <hpp/core/continuous-validation/solid-solid-collision.hh>
Public Member Functions | |
value_type | computeMaximalVelocity (vector_t &Vb) const |
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_t & | coefficients () const |
const JointPtr_t & | joint_a () const |
Get joint a. More... | |
const JointPtr_t & | joint_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... | |
IntervalValidationPtr_t | copy () const |
Public Member Functions inherited from hpp::core::continuousValidation::BodyPairCollision | |
bool | validateConfiguration (const value_type &t, interval_t &interval, ValidationReportPtr_t &report, const pinocchio::DeviceData &data) |
const CollisionPairs_t & | pairs () const |
CollisionPairs_t & | pairs () |
value_type | maximalVelocity () const |
value_type | securityMargin () const |
Get security margin. More... | |
void | securityMargin (const value_type &securityMargin) |
Set security margin. More... | |
Public Member Functions inherited from hpp::core::continuousValidation::IntervalValidation | |
void | path (const PathPtr_t &path, bool reverse) |
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) |
static SolidSolidCollisionPtr_t | create (const JointPtr_t &joint_a, const JointPtr_t &joint_b, value_type tolerance) |
static SolidSolidCollisionPtr_t | createCopy (const SolidSolidCollisionPtr_t &other) |
Copy instance and return shared pointer. More... | |
Protected Member Functions | |
SolidSolidCollision (const JointPtr_t &joint_a, const JointPtr_t &joint_b, value_type tolerance) | |
SolidSolidCollision (const JointPtr_t &joint_a, const ConstObjectStdVector_t &objects_b, value_type tolerance) | |
SolidSolidCollision (const SolidSolidCollision &other) | |
Copy constructor. More... | |
void | init (const SolidSolidCollisionWkPtr_t &weak) |
Protected Member Functions inherited from hpp::core::continuousValidation::BodyPairCollision | |
BodyPairCollision (value_type tolerance) | |
BodyPairCollision (const BodyPairCollision &other) | |
Copy constructor. More... | |
virtual void | setReport (ValidationReportPtr_t &report, fcl::CollisionResult result, CollisionPair_t _pair) const |
Protected Member Functions inherited from hpp::core::continuousValidation::IntervalValidation | |
IntervalValidation (value_type tolerance) | |
IntervalValidation (const IntervalValidation &other) | |
Additional Inherited Members | |
Public Types inherited from hpp::core::continuousValidation::BodyPairCollision | |
typedef std::pair< CollisionObjectConstPtr_t, CollisionObjectConstPtr_t > | CollisionPair_t |
typedef std::vector< CollisionPair_t > | CollisionPairs_t |
Protected Types inherited from hpp::core::continuousValidation::IntervalValidation | |
typedef boost::icl::continuous_interval< value_type > | continuous_interval |
typedef boost::icl::interval_set< value_type > | interval_set |
Protected Attributes inherited from hpp::core::continuousValidation::IntervalValidation | |
PathPtr_t | path_ |
value_type | tolerance_ |
bool | reverse_ |
bool | refine_ |
bool | valid_ |
interval_set | validInterval_ |
Computation of collision-free sub-intervals of a path
This class derives from BodyPairCollision and validates a subinterval of a path for collision between to robot bodies of between a robot body and the environment. The robot body should be part of an open kinematic chain.
See this document for details.
|
protected |
Constructor of inter-body collision checking
joint_a,joint_b | joint of the bodies to test for collision |
tolerance | allowed penetration should be positive |
|
protected |
Constructor of collision checking with the environment
joint_a | joint of the body to test for collision with the environment |
objects_b | environment objects for the collision checking |
tolerance | allowed penetration should be positive |
|
inlineprotected |
Copy constructor.
|
virtual |
Reimplemented from hpp::core::continuousValidation::BodyPairCollision.
|
inline |
|
virtual |
Compute maximal velocity for a given velocity bound
Vb | velocity |
Implements hpp::core::continuousValidation::BodyPairCollision.
|
virtual |
|
static |
Create instance and return shared pointer
joint_a | joint of the body to test for collision with the environment |
objects_b | environment objects for the collision checking |
tolerance | allowed penetration should be positive |
|
static |
Create instance and return shared pointer
joint_a,joint_b | joint of the bodies to test for collision |
tolerance | allowed penetrationd be positive |
|
static |
Copy instance and return shared pointer.
|
inlinevirtual |
Returns joint A index or -1 if no such joint exists.
Reimplemented from hpp::core::continuousValidation::BodyPairCollision.
|
inlinevirtual |
Returns joint B index or -1 if no such joint exists.
Reimplemented from hpp::core::continuousValidation::BodyPairCollision.
|
protected |
|
inline |
Get joint a.
|
inline |
Get joint b.
|
virtual |
|
virtual |
|
virtual |
Reimplemented from hpp::core::continuousValidation::BodyPairCollision.