|
hpp-core 6.0.0
Implement basic classes for canonical path planning for kinematic chains.
|
#include <hpp/core/continuous-validation/dichotomy.hh>


Public Member Functions | |
| virtual | ~Dichotomy () |
Public Member Functions inherited from hpp::core::ContinuousValidation | |
| 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) |
| virtual void | setSecurityMarginBetweenBodies (const std::string &body_a, const std::string &body_b, const value_type &margin) |
| void | addIntervalValidation (const IntervalValidationPtr_t &intervalValidation) |
| value_type | tolerance () const |
| Get tolerance value. | |
| value_type | breakDistance () const |
| void | breakDistance (value_type distance) |
| DevicePtr_t | robot () const |
| void | initialize () |
| virtual | ~ContinuousValidation () |
| template<class Delegate > | |
| void | add (const Delegate &delegate) |
| template<class Delegate > | |
| void | reset () |
Public Member Functions inherited from hpp::core::PathValidation | |
| virtual bool | validate (ConfigurationIn_t q, ValidationReportPtr_t &report) |
| virtual | ~PathValidation () |
Public Member Functions inherited from hpp::core::ObstacleUserInterface | |
| virtual | ~ObstacleUserInterface ()=default |
Static Public Member Functions | |
| static DichotomyPtr_t | create (const DevicePtr_t &robot, const value_type &tolerance) |
Protected Member Functions | |
| Dichotomy (const DevicePtr_t &robot, const value_type &tolerance) | |
| void | init (const DichotomyWkPtr_t weak) |
| Store weak pointer to itself. | |
Protected Member Functions inherited from hpp::core::ContinuousValidation | |
| 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. | |
Protected Member Functions inherited from hpp::core::PathValidation | |
| PathValidation () | |
Additional Inherited Members | |
Protected Types inherited from hpp::core::ContinuousValidation | |
| typedef continuousValidation::IntervalValidations_t | IntervalValidations_t |
Static Protected Member Functions inherited from hpp::core::ContinuousValidation | |
| static void | setPath (IntervalValidations_t &intervalValidations, const PathPtr_t &path, bool reverse) |
Protected Attributes inherited from hpp::core::ContinuousValidation | |
| DevicePtr_t | robot_ |
| value_type | tolerance_ |
| value_type | breakDistance_ |
| IntervalValidations_t | intervalValidations_ |
| All BodyPairValidation to validate. | |
| IntervalValidations_t | disabledBodyPairCollisions_ |
| BodyPairCollision for which collision is disabled. | |
| pinocchio::Pool< IntervalValidations_t > | bodyPairCollisionPool_ |
| value_type | stepSize_ |
Continuous validation of a path
This class is a specialization of ContinuousValidation.
The interval validation is performed by