hpp-core
4.9.0
Implement basic classes for canonical path planning for kinematic chains.
|
#include <hpp/core/continuous-validation/body-pair-collision.hh>
Public Types | |
typedef std::pair< CollisionObjectConstPtr_t, CollisionObjectConstPtr_t > | CollisionPair_t |
typedef std::vector< CollisionPair_t > | CollisionPairs_t |
Public Member Functions | |
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 |
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 |
Security margin | |
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 |
virtual IntervalValidationPtr_t | copy () const =0 |
Protected Member Functions | |
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 | |
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 aims at validating a path for the absence of collision between two bodies of a robot, or between a robot body and the environment. Bodies are considered as rigid.
If the bodies are part of an open kinematic chain, the computations are performed by class SolidSolidCollision.
With this abstraction, other bodies (like legs of a parallel robot) can also be checked for collision. In this case, the specialized class needs to implement method computeMaximalVelocity , taking into account the constrained motion of the legs implied by the closure of the kinematic chain.
See this document for details.
typedef std::pair<CollisionObjectConstPtr_t, CollisionObjectConstPtr_t> hpp::core::continuousValidation::BodyPairCollision::CollisionPair_t |
typedef std::vector<CollisionPair_t> hpp::core::continuousValidation::BodyPairCollision::CollisionPairs_t |
|
inlineprotected |
Constructor of body pair collision
tolerance | allowed penetration should be positive |
|
inlineprotected |
Copy constructor.
|
inlinevirtual |
Reimplemented in hpp::core::continuousValidation::SolidSolidCollision.
|
inlinevirtual |
Returns joint A index or -1 if no such joint exists.
Reimplemented in hpp::core::continuousValidation::SolidSolidCollision.
|
inlinevirtual |
Returns joint B index or -1 if no such joint exists.
Reimplemented in hpp::core::continuousValidation::SolidSolidCollision.
|
inline |
|
pure virtual |
Implements hpp::core::continuousValidation::IntervalValidation.
Implemented in hpp::core::continuousValidation::SolidSolidCollision.
|
inline |
|
inline |
|
pure virtual |
Implements hpp::core::continuousValidation::IntervalValidation.
Implemented in hpp::core::continuousValidation::SolidSolidCollision.
|
inlinevirtual |
Reimplemented in hpp::core::continuousValidation::SolidSolidCollision.
|
inline |
Get security margin.
|
inline |
Set security margin.
|
inlineprotectedvirtual |
|
virtual |
Validate interval centered on a path parameter
t | parameter value in the path interval of definition | |
[in,out] | interval | as input, interval over which collision checking must be performed. As output, interval over which pair is collision-free, not necessarily included in definition interval. |
report | the collision validation report |
Implements hpp::core::continuousValidation::IntervalValidation.