Set and solve a path planning problem. More...
#include <hpp/core/problem-solver.hh>
Public Types | |
| typedef std::vector< PathOptimizerPtr_t > | PathOptimizers_t | 
| typedef std::vector< std::string > | PathOptimizerTypes_t | 
| typedef std::vector< std::string > | ConfigValidationTypes_t | 
Public Member Functions | |
| virtual | ~ProblemSolver () | 
| Destructor.  More... | |
| void | robotType (const std::string &type) | 
| Set robot type.  More... | |
| const std::string & | robotType () const | 
| Get robot type.  More... | |
| DevicePtr_t | createRobot (const std::string &name) | 
| Create a robot of a type defined by method setRobotType.  More... | |
| virtual void | robot (const DevicePtr_t &robot) | 
| Set robot.  More... | |
| const DevicePtr_t & | robot () const | 
| Get robot.  More... | |
| ProblemPtr_t | problem () | 
| Get pointer to problem.  More... | |
| const ConfigurationPtr_t & | initConfig () const | 
| Get shared pointer to initial configuration.  More... | |
| virtual void | initConfig (const ConfigurationPtr_t &config) | 
| Set initial configuration.  More... | |
| const Configurations_t & | goalConfigs () const | 
| Get number of goal configuration.  More... | |
| virtual void | addGoalConfig (const ConfigurationPtr_t &config) | 
| Add goal configuration.  More... | |
| void | resetGoalConfigs () | 
| Reset the set of goal configurations.  More... | |
| virtual void | pathPlannerType (const std::string &type) | 
| Set path planner type.  More... | |
| const std::string & | pathPlannerType () const | 
| void | distanceType (const std::string &type) | 
| Set distance type.  More... | |
| const std::string & | distanceType () const | 
| void | steeringMethodType (const std::string &type) | 
| Set steering method type.  More... | |
| const std::string & | steeringMethodType () const | 
| void | configurationShooterType (const std::string &type) | 
| Set configuration shooter type.  More... | |
| const std::string & | configurationShooterType () const | 
| const PathPlannerPtr_t & | pathPlanner () const | 
| Get path planner.  More... | |
| void | addPathOptimizer (const std::string &type) | 
| Add a path optimizer in the vector.  More... | |
| const PathOptimizerTypes_t & | pathOptimizerTypes () const | 
| void | clearPathOptimizers () | 
| Clear the vector of path optimizers.  More... | |
| const PathOptimizerPtr_t & | pathOptimizer (std::size_t rank) const | 
| Get path optimizer at given rank.  More... | |
| void | optimizePath (PathVectorPtr_t path) | 
| Optimize path.  More... | |
| virtual void | pathValidationType (const std::string &type, const value_type &tolerance) | 
| Set path validation method.  More... | |
| const std::string & | pathValidationType (value_type &tolerance) const | 
| void | pathProjectorType (const std::string &type, const value_type &step) | 
| Set path projector method.  More... | |
| const std::string & | pathProjectorType (value_type &tolerance) const | 
| Get path projector current type and get tolerance.  More... | |
| virtual void | addConfigValidation (const std::string &type) | 
| Add a config validation method.  More... | |
| const ConfigValidationTypes_t | configValidationTypes () | 
| Get config validation current types.  More... | |
| void | clearConfigValidations () | 
| void | addConfigValidationBuilder (const std::string &type, const ConfigValidationBuilder_t &builder) | 
| Add a new available config validation method.  More... | |
| const RoadmapPtr_t & | roadmap () const | 
| virtual void | resetProblem () | 
| Create new problem.  More... | |
| virtual void | resetRoadmap () | 
| Reset the roadmap.  More... | |
| const ObjectStdVector_t & | collisionObstacles () const | 
| Local vector of objects considered for collision detection.  More... | |
| const ObjectStdVector_t & | distanceObstacles () const | 
| Local vector of objects considered for distance computation.  More... | |
| void | roadmap (const RoadmapPtr_t &roadmap) | 
| Set the roadmap.  More... | |
| void | initDistance () | 
| Initialize distance.  More... | |
| void | initSteeringMethod () | 
| Initialize steering method.  More... | |
| void | initPathProjector () | 
| Initialize path projector.  More... | |
| void | initPathValidation () | 
| Set path validation by calling path validation factory.  More... | |
| void | initConfigValidation () | 
| Set config validation by calling config validation factories.  More... | |
| void | initValidations () | 
| Initialize the config and path validations and add the obstacles.  More... | |
| virtual void | initProblemTarget () | 
| Initialize the problem target by calling the path validation factory.  More... | |
Constraints  | |
| void | addConstraint (const ConstraintPtr_t &constraint) | 
| Add a constraint.  More... | |
| const ConstraintSetPtr_t & | constraints () const | 
| Get constraint set.  More... | |
| virtual void | resetConstraints () | 
| Reset constraint set.  More... | |
| virtual void | addNumericalConstraintToConfigProjector (const std::string &configProjName, const std::string &constraintName, const std::size_t priority=0) | 
| Add numerical constraint to the config projector.  More... | |
| virtual void | addLockedJointToConfigProjector (const std::string &configProjName, const std::string &lockedJointName) HPP_CORE_DEPRECATED | 
| Add locked joint to the config projector.  More... | |
| void | addNumericalConstraint (const std::string &name, const constraints::ImplicitPtr_t &constraint) | 
| Add a a numerical constraint in local map.  More... | |
| void | comparisonType (const std::string &name, const ComparisonTypes_t types) | 
| Set the comparison types of a constraint.  More... | |
| void | comparisonType (const std::string &name, const ComparisonType &type) | 
| ComparisonTypes_t | comparisonType (const std::string &name) const | 
| constraints::ImplicitPtr_t | numericalConstraint (const std::string &name) | 
| Get constraint with given name.  More... | |
| void | computeValueAndJacobian (const Configuration_t &configuration, vector_t &value, matrix_t &jacobian) const | 
| Compute value and Jacobian of numerical constraints.  More... | |
| void | maxIterProjection (size_type iterations) | 
| Set maximal number of iterations in config projector.  More... | |
| size_type | maxIterProjection () const | 
| Get maximal number of iterations in config projector.  More... | |
| void | maxIterPathPlanning (size_type iterations) | 
| Set maximal number of iterations in config projector.  More... | |
| size_type | maxIterPathPlanning () const | 
| Get maximal number of iterations in config projector.  More... | |
| void | setTimeOutPathPlanning (double timeOut) | 
| set time out for the path planning ( in seconds)  More... | |
| double | getTimeOutPathPlanning () | 
| set time out for the path planning ( in seconds)  More... | |
| void | errorThreshold (const value_type &threshold) | 
| Set error threshold in config projector.  More... | |
| value_type | errorThreshold () const | 
| Get errorimal number of threshold in config projector.  More... | |
Solve problem and get paths  | |
| void | createPathOptimizers () | 
| Create Path optimizer if needed.  More... | |
| virtual bool | prepareSolveStepByStep () | 
| Prepare the solver for a step by step planning.  More... | |
| virtual bool | executeOneStep () | 
| Execute one step of the planner.  More... | |
| virtual void | finishSolveStepByStep () | 
| Finish the solving procedure The path optimizer is not called.  More... | |
| virtual void | solve () | 
| Set and solve the problem.  More... | |
| bool | directPath (ConfigurationIn_t start, ConfigurationIn_t end, bool validate, std::size_t &pathId, std::string &report) | 
| Make direct connection between two configurations.  More... | |
| void | addConfigToRoadmap (const ConfigurationPtr_t &config) | 
| Add random configuration into roadmap as new node.  More... | |
| void | addEdgeToRoadmap (const ConfigurationPtr_t &config1, const ConfigurationPtr_t &config2, const PathPtr_t &path) | 
| Add an edge between two roadmap nodes.  More... | |
| void | interrupt () | 
| Interrupt path planning and path optimization.  More... | |
| std::size_t | addPath (const PathVectorPtr_t &path) | 
| Add a path.  More... | |
| void | erasePath (std::size_t pathId) | 
| Erase a path.  More... | |
| const PathVectors_t & | paths () const | 
| Return vector of paths.  More... | |
Obstacles  | |
| virtual void | addObstacle (const DevicePtr_t &device, bool collision, bool distance) | 
| Add collision objects of a device as obstacles to the list.  More... | |
| virtual void | addObstacle (const CollisionObjectPtr_t &inObject, bool collision, bool distance) | 
| Add obstacle to the list.  More... | |
| virtual void | removeObstacle (const std::string &name) | 
| Remove obstacle from the list.  More... | |
| virtual void | addObstacle (const std::string &name, FclCollisionObject &inObject, bool collision, bool distance) | 
| Add obstacle to the list.  More... | |
| void | removeObstacleFromJoint (const std::string &jointName, const std::string &obstacleName) | 
| Remove collision pair between a joint and an obstacle.  More... | |
| void | cutObstacle (const std::string &name, const fcl::AABB &aabb) | 
| Extract from the obstacle the part that can collide with aabb.  More... | |
| void | filterCollisionPairs () | 
| Build matrix of relative motions between joints.  More... | |
| CollisionObjectPtr_t | obstacle (const std::string &name) const | 
| Get obstacle by name Throws if obstacle does not exists.  More... | |
| const Transform3f & | obstacleFramePosition (const std::string &name) const | 
| Get obstacle frame position by name Throws if obstacle frame does not exists.  More... | |
| std::list< std::string > | obstacleNames (bool collision, bool distance) const | 
| Get list of obstacle names.  More... | |
| const DistanceBetweenObjectsPtr_t & | distanceBetweenObjects () const | 
| Return list of pair of distance computations.  More... | |
Static Public Member Functions | |
| static ProblemSolverPtr_t | create () | 
| Create instance and return pointer.  More... | |
Protected Member Functions | |
| ProblemSolver () | |
| Constructor.  More... | |
| void | problem (ProblemPtr_t problem) | 
| Set pointer to problem.  More... | |
| virtual void | initializeProblem (ProblemPtr_t problem) | 
| Initialize the new problem.  More... | |
Protected Attributes | |
| ConstraintSetPtr_t | constraints_ | 
| Store constraints until call to solve.  More... | |
| DevicePtr_t | robot_ | 
| Robot.  More... | |
| ProblemPtr_t | problem_ | 
| Problem.  More... | |
| PathPlannerPtr_t | pathPlanner_ | 
| RoadmapPtr_t | roadmap_ | 
| Store roadmap.  More... | |
| PathVectors_t | paths_ | 
| Paths.  More... | |
| std::string | pathProjectorType_ | 
| Path projector method.  More... | |
| value_type | pathProjectorTolerance_ | 
| Tolerance of path projector.  More... | |
| std::string | pathPlannerType_ | 
| Path planner.  More... | |
| ProblemTargetPtr_t | target_ | 
| Shared pointer to the problem target.  More... | |
Set and solve a path planning problem.
This class is a container that does the interface between hpp-core library and component to be running in a middleware like CORBA or ROS.
| typedef std::vector<std::string> hpp::core::ProblemSolver::ConfigValidationTypes_t | 
| typedef std::vector<PathOptimizerPtr_t> hpp::core::ProblemSolver::PathOptimizers_t | 
| typedef std::vector<std::string> hpp::core::ProblemSolver::PathOptimizerTypes_t | 
      
  | 
  virtual | 
Destructor.
      
  | 
  protected | 
Constructor.
Call create to create an instance.
| void hpp::core::ProblemSolver::addConfigToRoadmap | ( | const ConfigurationPtr_t & | config | ) | 
Add random configuration into roadmap as new node.
      
  | 
  virtual | 
Add a config validation method.
| type | name of new config validation method Config validation methods are used to validate individual configurations of the robot. | 
| void hpp::core::ProblemSolver::addConfigValidationBuilder | ( | const std::string & | type, | 
| const ConfigValidationBuilder_t & | builder | ||
| ) | 
Add a new available config validation method.
| void hpp::core::ProblemSolver::addConstraint | ( | const ConstraintPtr_t & | constraint | ) | 
Add a constraint.
| void hpp::core::ProblemSolver::addEdgeToRoadmap | ( | const ConfigurationPtr_t & | config1, | 
| const ConfigurationPtr_t & | config2, | ||
| const PathPtr_t & | path | ||
| ) | 
Add an edge between two roadmap nodes.
| config1 | configuration of start node, | 
| config2 | configuration of destination node, | 
| path | path to store in the edge. | 
Check that nodes containing config1 and config2 exist in the roadmap.
      
  | 
  virtual | 
Add goal configuration.
      
  | 
  virtual | 
Add locked joint to the config projector.
| configProjName | Name given to config projector if created by this method. | 
| lockedJointName | name of the locked joint as stored in internal map. Build the config projector if not yet constructed. | 
      
  | 
  inline | 
Add a a numerical constraint in local map.
| name | name of the numerical constraint as stored in local map, | 
| constraint | numerical constraint | 
Numerical constraints are to be inserted in the ConfigProjector of the constraint set.
      
  | 
  virtual | 
Add numerical constraint to the config projector.
| configProjName | Name given to config projector if created by this method. | 
| constraintName | name of the function as stored in internal map. Build the config projector if not yet constructed. | 
      
  | 
  virtual | 
Add collision objects of a device as obstacles to the list.
| device | the Device to be added. | 
| collision | whether collision checking should be performed for this object. | 
| distance | whether distance computation should be performed for this object. | 
      
  | 
  virtual | 
Add obstacle to the list.
| inObject | a new object. | 
| collision | whether collision checking should be performed for this object. | 
| distance | whether distance computation should be performed for this object. | 
      
  | 
  virtual | 
Add obstacle to the list.
| inObject | a new object. | 
| collision | whether collision checking should be performed for this object. | 
| distance | whether distance computation should be performed for this object. | 
      
  | 
  inline | 
Add a path.
| void hpp::core::ProblemSolver::addPathOptimizer | ( | const std::string & | type | ) | 
Add a path optimizer in the vector.
| name | of the type of path optimizer that should be added | 
| void hpp::core::ProblemSolver::clearConfigValidations | ( | ) | 
| void hpp::core::ProblemSolver::clearPathOptimizers | ( | ) | 
Clear the vector of path optimizers.
| const ObjectStdVector_t& hpp::core::ProblemSolver::collisionObstacles | ( | ) | const | 
Local vector of objects considered for collision detection.
| void hpp::core::ProblemSolver::comparisonType | ( | const std::string & | name, | 
| const ComparisonTypes_t | types | ||
| ) | 
Set the comparison types of a constraint.
| name | name of the differentiable function. | 
| void hpp::core::ProblemSolver::comparisonType | ( | const std::string & | name, | 
| const ComparisonType & | type | ||
| ) | 
| ComparisonTypes_t hpp::core::ProblemSolver::comparisonType | ( | const std::string & | name | ) | const | 
| void hpp::core::ProblemSolver::computeValueAndJacobian | ( | const Configuration_t & | configuration, | 
| vector_t & | value, | ||
| matrix_t & | jacobian | ||
| ) | const | 
Compute value and Jacobian of numerical constraints.
| configuration | input configuration | 
| value | values of the numerical constraints stacked in a unique vector, | 
| jacobian | Jacobian of the numerical constraints stacked in a unique matrix. | 
Columns of the Jacobian corresponding to locked joints are omitted, columns corresponding to passive dofs are set to 0.
| void hpp::core::ProblemSolver::configurationShooterType | ( | const std::string & | type | ) | 
Set configuration shooter type.
      
  | 
  inline | 
      
  | 
  inline | 
Get config validation current types.
      
  | 
  inline | 
Get constraint set.
      
  | 
  static | 
Create instance and return pointer.
| void hpp::core::ProblemSolver::createPathOptimizers | ( | ) | 
Create Path optimizer if needed.
If a path optimizer is already set, do nothing. Type of optimizer is determined by method selectPathOptimizer.
| DevicePtr_t hpp::core::ProblemSolver::createRobot | ( | const std::string & | name | ) | 
Create a robot of a type defined by method setRobotType.
| name | name of the robot | 
Robot is stored in problemSolver.
| void hpp::core::ProblemSolver::cutObstacle | ( | const std::string & | name, | 
| const fcl::AABB & | aabb | ||
| ) | 
Extract from the obstacle the part that can collide with aabb.
| bool hpp::core::ProblemSolver::directPath | ( | ConfigurationIn_t | start, | 
| ConfigurationIn_t | end, | ||
| bool | validate, | ||
| std::size_t & | pathId, | ||
| std::string & | report | ||
| ) | 
Make direct connection between two configurations.
| start,end | the configurations to link. | 
| validate | whether path should be validated. If true, path validation is called and only valid part of path is inserted in the path vector. | 
| pathId | Id of the path that is inserted in the path vector, | 
| report | Reason for non validation if relevant. return false if direct path is not fully valid | 
      
  | 
  inline | 
Return list of pair of distance computations.
| const ObjectStdVector_t& hpp::core::ProblemSolver::distanceObstacles | ( | ) | const | 
Local vector of objects considered for distance computation.
| void hpp::core::ProblemSolver::distanceType | ( | const std::string & | type | ) | 
Set distance type.
      
  | 
  inline | 
      
  | 
  inline | 
Erase a path.
| void hpp::core::ProblemSolver::errorThreshold | ( | const value_type & | threshold | ) | 
Set error threshold in config projector.
      
  | 
  inline | 
Get errorimal number of threshold in config projector.
      
  | 
  virtual | 
Execute one step of the planner.
| void hpp::core::ProblemSolver::filterCollisionPairs | ( | ) | 
Build matrix of relative motions between joints.
      
  | 
  virtual | 
Finish the solving procedure The path optimizer is not called.
      
  | 
  inline | 
set time out for the path planning ( in seconds)
| const Configurations_t& hpp::core::ProblemSolver::goalConfigs | ( | ) | const | 
Get number of goal configuration.
      
  | 
  inline | 
Get shared pointer to initial configuration.
      
  | 
  virtual | 
Set initial configuration.
| void hpp::core::ProblemSolver::initConfigValidation | ( | ) | 
Set config validation by calling config validation factories.
| void hpp::core::ProblemSolver::initDistance | ( | ) | 
Initialize distance.
Set distance by calling the distance factory
      
  | 
  protectedvirtual | 
Initialize the new problem.
| problem | is inserted in the ProblemSolver and initialized. | 
| void hpp::core::ProblemSolver::initPathProjector | ( | ) | 
Initialize path projector.
Set path projector by calling path projector factory
| void hpp::core::ProblemSolver::initPathValidation | ( | ) | 
Set path validation by calling path validation factory.
      
  | 
  virtual | 
Initialize the problem target by calling the path validation factory.
| void hpp::core::ProblemSolver::initSteeringMethod | ( | ) | 
Initialize steering method.
Set steering method by calling the steering method factory
| void hpp::core::ProblemSolver::initValidations | ( | ) | 
Initialize the config and path validations and add the obstacles.
| void hpp::core::ProblemSolver::interrupt | ( | ) | 
Interrupt path planning and path optimization.
| void hpp::core::ProblemSolver::maxIterPathPlanning | ( | size_type | iterations | ) | 
Set maximal number of iterations in config projector.
      
  | 
  inline | 
Get maximal number of iterations in config projector.
| void hpp::core::ProblemSolver::maxIterProjection | ( | size_type | iterations | ) | 
Set maximal number of iterations in config projector.
      
  | 
  inline | 
Get maximal number of iterations in config projector.
      
  | 
  inline | 
Get constraint with given name.
| CollisionObjectPtr_t hpp::core::ProblemSolver::obstacle | ( | const std::string & | name | ) | const | 
Get obstacle by name Throws if obstacle does not exists.
| const Transform3f& hpp::core::ProblemSolver::obstacleFramePosition | ( | const std::string & | name | ) | const | 
Get obstacle frame position by name Throws if obstacle frame does not exists.
| std::list<std::string> hpp::core::ProblemSolver::obstacleNames | ( | bool | collision, | 
| bool | distance | ||
| ) | const | 
Get list of obstacle names.
| collision | whether to return collision obstacle names | 
| distance | whether to return distance obstacle names | 
| void hpp::core::ProblemSolver::optimizePath | ( | PathVectorPtr_t | path | ) | 
Optimize path.
| path | path to optimize Build vector of path optimizers if needed | 
      
  | 
  inline | 
Get path optimizer at given rank.
      
  | 
  inline | 
      
  | 
  inline | 
Get path planner.
      
  | 
  virtual | 
Set path planner type.
      
  | 
  inline | 
| void hpp::core::ProblemSolver::pathProjectorType | ( | const std::string & | type, | 
| const value_type & | step | ||
| ) | 
Set path projector method.
| type | name of new path validation method | 
| step | discontinuity tolerance | 
      
  | 
  inline | 
Get path projector current type and get tolerance.
      
  | 
  inline | 
Return vector of paths.
      
  | 
  virtual | 
Set path validation method.
| type | name of new path validation method | 
| tolerance | acceptable penetration for path validation Path validation methods are used to validate edges in path planning path optimization methods. | 
      
  | 
  inline | 
      
  | 
  virtual | 
Prepare the solver for a step by step planning.
and try to make direct connections (call PathPlanner::tryDirectPath)
      
  | 
  inline | 
Get pointer to problem.
      
  | 
  protected | 
Set pointer to problem.
      
  | 
  virtual | 
Remove obstacle from the list.
| name | name of the obstacle | 
| void hpp::core::ProblemSolver::removeObstacleFromJoint | ( | const std::string & | jointName, | 
| const std::string & | obstacleName | ||
| ) | 
Remove collision pair between a joint and an obstacle.
| jointName | name of the joint, | 
| obstacleName | name of the obstacle | 
      
  | 
  virtual | 
Reset constraint set.
| void hpp::core::ProblemSolver::resetGoalConfigs | ( | ) | 
Reset the set of goal configurations.
      
  | 
  virtual | 
Create new problem.
      
  | 
  virtual | 
Reset the roadmap.
      
  | 
  inline | 
      
  | 
  inline | 
Set the roadmap.
      
  | 
  virtual | 
Set robot.
| const DevicePtr_t& hpp::core::ProblemSolver::robot | ( | ) | const | 
Get robot.
| void hpp::core::ProblemSolver::robotType | ( | const std::string & | type | ) | 
Set robot type.
| type | type of the robots that will be created later | 
| const std::string& hpp::core::ProblemSolver::robotType | ( | ) | const | 
Get robot type.
      
  | 
  inline | 
set time out for the path planning ( in seconds)
      
  | 
  virtual | 
Set and solve the problem.
| void hpp::core::ProblemSolver::steeringMethodType | ( | const std::string & | type | ) | 
Set steering method type.
      
  | 
  inline | 
| Container<AffordanceConfig_t> hpp::core::ProblemSolver::affordanceConfigs | 
Container of AffordanceConfig_t.
| Container<AffordanceObjects_t> hpp::core::ProblemSolver::affordanceObjects | 
Container of AffordanceObjects_t.
| Container<CenterOfMassComputationPtr_t> hpp::core::ProblemSolver::centerOfMassComputations | 
Container of CenterOfMassComputation.
| Container<ConfigurationShooterBuilder_t> hpp::core::ProblemSolver::configurationShooters | 
Container of static method that creates a ConfigurationShooter with a robot as input.
| Container<ConfigValidationBuilder_t> hpp::core::ProblemSolver::configValidations | 
Container of static method that creates a ConfigValidation with a robot as input.
      
  | 
  protected | 
Store constraints until call to solve.
| Container<DistanceBuilder_t> hpp::core::ProblemSolver::distances | 
| Container<JointAndShapes_t> hpp::core::ProblemSolver::jointAndShapes | 
Container of JointAndShapes_t.
| Member_lockedJoints_in_class_ProblemSolver_has_been_removed_use_member_numericalConstraints_instead hpp::core::ProblemSolver::lockedJoints | 
member lockedJoints has been removed.
LockedJointPtr_t instances are now stored with constraints::ImplicitPtr_t in member numericalConstraints.
| Container<constraints::ImplicitPtr_t> hpp::core::ProblemSolver::numericalConstraints | 
Container of constraints::Implicit.
| Container<segments_t> hpp::core::ProblemSolver::passiveDofs | 
Container of passive DoFs (as segments_t)
| Container<PathOptimizerBuilder_t> hpp::core::ProblemSolver::pathOptimizers | 
Container of static method that creates a PathOptimizer with a problem as input.
      
  | 
  protected | 
| Container<PathPlannerBuilder_t> hpp::core::ProblemSolver::pathPlanners | 
Container of static method that creates a PathPlanner with a problem and a roadmap as input.
      
  | 
  protected | 
Path planner.
| Container<PathProjectorBuilder_t> hpp::core::ProblemSolver::pathProjectors | 
Container of static method that creates a PathProjection with a problem and a tolerance as input.
      
  | 
  protected | 
Tolerance of path projector.
      
  | 
  protected | 
Path projector method.
      
  | 
  protected | 
Paths.
| Container<PathValidationBuilder_t> hpp::core::ProblemSolver::pathValidations | 
Container of static method that creates a PathValidation with a robot and a tolerance as input.
      
  | 
  protected | 
      
  | 
  protected | 
Store roadmap.
      
  | 
  protected | 
Robot.
| Container<RobotBuilder_t> hpp::core::ProblemSolver::robots | 
Container of static method that creates a Robot with string as input.
| Container<SteeringMethodBuilder_t> hpp::core::ProblemSolver::steeringMethods | 
Container of static method that creates a SteeringMethod with a problem as input.
      
  | 
  protected | 
Shared pointer to the problem target.