hpp-core  4.9.0
Implement basic classes for canonical path planning for kinematic chains.
hpp::core::ProblemSolver Class Reference

#include <hpp/core/problem-solver.hh>

Collaboration diagram for hpp::core::ProblemSolver:

Public Types

typedef std::vector< PathOptimizerPtr_tPathOptimizers_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)
 
const std::string & robotType () const
 Get robot type. More...
 
DevicePtr_t createRobot (const std::string &name)
 
virtual void robot (const DevicePtr_t &robot)
 Set robot. More...
 
const DevicePtr_trobot () const
 Get robot. More...
 
ProblemPtr_t problem ()
 Get pointer to problem. More...
 
const ConfigurationPtr_tinitConfig () const
 Get shared pointer to initial configuration. More...
 
virtual void initConfig (const ConfigurationPtr_t &config)
 Set initial configuration. More...
 
const Configurations_tgoalConfigs () 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_tpathPlanner () const
 Get path planner. More...
 
void addPathOptimizer (const std::string &type)
 
const PathOptimizerTypes_tpathOptimizerTypes () const
 
void clearPathOptimizers ()
 Clear the vector of path optimizers. More...
 
const PathOptimizerPtr_tpathOptimizer (std::size_t rank) const
 Get path optimizer at given rank. More...
 
void optimizePath (PathVectorPtr_t path)
 
virtual void pathValidationType (const std::string &type, const value_type &tolerance)
 
const std::string & pathValidationType (value_type &tolerance) const
 
void pathProjectorType (const std::string &type, const value_type &step)
 
const std::string & pathProjectorType (value_type &tolerance) const
 Get path projector current type and get tolerance. More...
 
virtual void addConfigValidation (const std::string &type)
 
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_troadmap () const
 
virtual void resetProblem ()
 Create new problem. More...
 
virtual void resetRoadmap ()
 
const ObjectStdVector_tcollisionObstacles () const
 Local vector of objects considered for collision detection. More...
 
const ObjectStdVector_tdistanceObstacles () const
 Local vector of objects considered for distance computation. More...
 
void roadmap (const RoadmapPtr_t &roadmap)
 Set the roadmap. More...
 
void initDistance ()
 
void initSteeringMethod ()
 
void initPathProjector ()
 
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_tconstraints () 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)
 
virtual void addLockedJointToConfigProjector (const std::string &configProjName, const std::string &lockedJointName) HPP_CORE_DEPRECATED
 
void addNumericalConstraint (const std::string &name, const constraints::ImplicitPtr_t &constraint)
 
void comparisonType (const std::string &name, const ComparisonTypes_t types)
 
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
 
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 ()
 
virtual bool prepareSolveStepByStep ()
 
virtual bool executeOneStep ()
 
virtual void finishSolveStepByStep ()
 
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)
 
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)
 
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_tpaths () const
 Return vector of paths. More...
 
Obstacles
virtual void addObstacle (const DevicePtr_t &device, bool collision, bool distance)
 
virtual void addObstacle (const CollisionObjectPtr_t &inObject, bool collision, bool distance)
 
virtual void removeObstacle (const std::string &name)
 
virtual void addObstacle (const std::string &name, FclCollisionObject &inObject, bool collision, bool distance)
 
void removeObstacleFromJoint (const std::string &jointName, const std::string &obstacleName)
 
void cutObstacle (const std::string &name, const fcl::AABB &aabb)
 
void filterCollisionPairs ()
 
CollisionObjectPtr_t obstacle (const std::string &name) const
 
const Transform3fobstacleFramePosition (const std::string &name) const
 
std::list< std::string > obstacleNames (bool collision, bool distance) const
 
const DistanceBetweenObjectsPtr_tdistanceBetweenObjects () const
 Return list of pair of distance computations. More...
 
pinocchio::GeomModelPtr_t obstacleGeomModel () const
 
pinocchio::GeomDataPtr_t obstacleGeomData () const
 

Static Public Member Functions

static ProblemSolverPtr_t create ()
 Create instance and return pointer. More...
 

Public Attributes

Container< RobotBuilder_trobots
 
Container< ConfigurationShooterBuilder_tconfigurationShooters
 
Container< SteeringMethodBuilder_tsteeringMethods
 
Container< DistanceBuilder_tdistances
 
Container< PathValidationBuilder_tpathValidations
 
Container< ConfigValidationBuilder_tconfigValidations
 
Container< PathProjectorBuilder_tpathProjectors
 
Container< PathPlannerBuilder_tpathPlanners
 
Container< PathOptimizerBuilder_tpathOptimizers
 
Container< constraints::ImplicitPtr_tnumericalConstraints
 Container of constraints::Implicit. More...
 
Member_lockedJoints_in_class_ProblemSolver_has_been_removed_use_member_numericalConstraints_instead lockedJoints
 
Container< CenterOfMassComputationPtr_tcenterOfMassComputations
 Container of CenterOfMassComputation. More...
 
Container< segments_tpassiveDofs
 Container of passive DoFs (as segments_t) More...
 
Container< JointAndShapes_tjointAndShapes
 Container of JointAndShapes_t. More...
 
Container< AffordanceObjects_taffordanceObjects
 Container of AffordanceObjects_t. More...
 
Container< AffordanceConfig_taffordanceConfigs
 Container of AffordanceConfig_t. More...
 

Protected Member Functions

 ProblemSolver ()
 
void problem (ProblemPtr_t problem)
 Set pointer to problem. More...
 
virtual void initializeProblem (ProblemPtr_t problem)
 

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...
 

Detailed Description

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.

Member Typedef Documentation

◆ ConfigValidationTypes_t

typedef std::vector<std::string> hpp::core::ProblemSolver::ConfigValidationTypes_t

◆ PathOptimizers_t

◆ PathOptimizerTypes_t

typedef std::vector<std::string> hpp::core::ProblemSolver::PathOptimizerTypes_t

Constructor & Destructor Documentation

◆ ~ProblemSolver()

virtual hpp::core::ProblemSolver::~ProblemSolver ( )
virtual

Destructor.

◆ ProblemSolver()

hpp::core::ProblemSolver::ProblemSolver ( )
protected

Constructor

Call create to create an instance.

Member Function Documentation

◆ addConfigToRoadmap()

void hpp::core::ProblemSolver::addConfigToRoadmap ( const ConfigurationPtr_t config)

Add random configuration into roadmap as new node.

◆ addConfigValidation()

virtual void hpp::core::ProblemSolver::addConfigValidation ( const std::string &  type)
virtual

Add a config validation method

Parameters
typename of new config validation method Config validation methods are used to validate individual configurations of the robot.

◆ addConfigValidationBuilder()

void hpp::core::ProblemSolver::addConfigValidationBuilder ( const std::string &  type,
const ConfigValidationBuilder_t builder 
)

Add a new available config validation method.

◆ addConstraint()

void hpp::core::ProblemSolver::addConstraint ( const ConstraintPtr_t constraint)

Add a constraint.

◆ addEdgeToRoadmap()

void hpp::core::ProblemSolver::addEdgeToRoadmap ( const ConfigurationPtr_t config1,
const ConfigurationPtr_t config2,
const PathPtr_t path 
)

Add an edge between two roadmap nodes.

Parameters
config1configuration of start node,
config2configuration of destination node,
pathpath to store in the edge.

Check that nodes containing config1 and config2 exist in the roadmap.

◆ addGoalConfig()

virtual void hpp::core::ProblemSolver::addGoalConfig ( const ConfigurationPtr_t config)
virtual

Add goal configuration.

◆ addLockedJointToConfigProjector()

virtual void hpp::core::ProblemSolver::addLockedJointToConfigProjector ( const std::string &  configProjName,
const std::string &  lockedJointName 
)
virtual

Add locked joint to the config projector

Parameters
configProjNameName given to config projector if created by this method.
lockedJointNamename of the locked joint as stored in internal map. Build the config projector if not yet constructed.
Deprecated:
LockedJoint instances are now handled as other numerical constraints. Call addNumericalConstraintToConfigProjector instead.

◆ addNumericalConstraint()

void hpp::core::ProblemSolver::addNumericalConstraint ( const std::string &  name,
const constraints::ImplicitPtr_t constraint 
)
inline

Add a a numerical constraint in local map.

Parameters
namename of the numerical constraint as stored in local map,
constraintnumerical constraint

Numerical constraints are to be inserted in the ConfigProjector of the constraint set.

◆ addNumericalConstraintToConfigProjector()

virtual void hpp::core::ProblemSolver::addNumericalConstraintToConfigProjector ( const std::string &  configProjName,
const std::string &  constraintName,
const std::size_t  priority = 0 
)
virtual

Add numerical constraint to the config projector

Parameters
configProjNameName given to config projector if created by this method.
constraintNamename of the function as stored in internal map. Build the config projector if not yet constructed.

◆ addObstacle() [1/3]

virtual void hpp::core::ProblemSolver::addObstacle ( const DevicePtr_t device,
bool  collision,
bool  distance 
)
virtual

Add collision objects of a device as obstacles to the list.

Parameters
devicethe Device to be added.
collisionwhether collision checking should be performed for this object.
distancewhether distance computation should be performed for this object.

◆ addObstacle() [2/3]

virtual void hpp::core::ProblemSolver::addObstacle ( const CollisionObjectPtr_t inObject,
bool  collision,
bool  distance 
)
virtual

Add obstacle to the list.

Parameters
inObjecta new object.
collisionwhether collision checking should be performed for this object.
distancewhether distance computation should be performed for this object.

◆ addObstacle() [3/3]

virtual void hpp::core::ProblemSolver::addObstacle ( const std::string &  name,
FclCollisionObject inObject,
bool  collision,
bool  distance 
)
virtual

Add obstacle to the list.

Parameters
inObjecta new object.
collisionwhether collision checking should be performed for this object.
distancewhether distance computation should be performed for this object.

◆ addPath()

std::size_t hpp::core::ProblemSolver::addPath ( const PathVectorPtr_t path)
inline

Add a path.

◆ addPathOptimizer()

void hpp::core::ProblemSolver::addPathOptimizer ( const std::string &  type)

Add a path optimizer in the vector

Parameters
nameof the type of path optimizer that should be added

◆ clearConfigValidations()

void hpp::core::ProblemSolver::clearConfigValidations ( )

◆ clearPathOptimizers()

void hpp::core::ProblemSolver::clearPathOptimizers ( )

Clear the vector of path optimizers.

◆ collisionObstacles()

const ObjectStdVector_t& hpp::core::ProblemSolver::collisionObstacles ( ) const

Local vector of objects considered for collision detection.

◆ comparisonType() [1/3]

void hpp::core::ProblemSolver::comparisonType ( const std::string &  name,
const ComparisonTypes_t  types 
)

Set the comparison types of a constraint.

Parameters
namename of the differentiable function.

◆ comparisonType() [2/3]

void hpp::core::ProblemSolver::comparisonType ( const std::string &  name,
const ComparisonType type 
)

◆ comparisonType() [3/3]

ComparisonTypes_t hpp::core::ProblemSolver::comparisonType ( const std::string &  name) const

◆ computeValueAndJacobian()

void hpp::core::ProblemSolver::computeValueAndJacobian ( const Configuration_t configuration,
vector_t value,
matrix_t jacobian 
) const

Compute value and Jacobian of numerical constraints

Parameters
configurationinput configuration
Return values
valuevalues of the numerical constraints stacked in a unique vector,
jacobianJacobian 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.

◆ configurationShooterType() [1/2]

void hpp::core::ProblemSolver::configurationShooterType ( const std::string &  type)

Set configuration shooter type.

◆ configurationShooterType() [2/2]

const std::string& hpp::core::ProblemSolver::configurationShooterType ( ) const
inline

◆ configValidationTypes()

const ConfigValidationTypes_t hpp::core::ProblemSolver::configValidationTypes ( )
inline

Get config validation current types.

◆ constraints()

const ConstraintSetPtr_t& hpp::core::ProblemSolver::constraints ( ) const
inline

Get constraint set.

◆ create()

static ProblemSolverPtr_t hpp::core::ProblemSolver::create ( )
static

Create instance and return pointer.

◆ createPathOptimizers()

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.

◆ createRobot()

DevicePtr_t hpp::core::ProblemSolver::createRobot ( const std::string &  name)

Create a robot of a type defined by method setRobotType

Parameters
namename of the robot

Robot is stored in problemSolver.

◆ cutObstacle()

void hpp::core::ProblemSolver::cutObstacle ( const std::string &  name,
const fcl::AABB aabb 
)

Extract from the obstacle the part that can collide with aabb

Warning
the obstacle is removed if there are not possible collision.

◆ directPath()

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

Parameters
start,endthe configurations to link.
validatewhether path should be validated. If true, path validation is called and only valid part of path is inserted in the path vector.
Return values
pathIdId of the path that is inserted in the path vector,
reportReason for non validation if relevant. return false if direct path is not fully valid
Note
If path is only partly valid, valid part starting at start configuration is inserted in path vector.

◆ distanceBetweenObjects()

const DistanceBetweenObjectsPtr_t& hpp::core::ProblemSolver::distanceBetweenObjects ( ) const
inline

Return list of pair of distance computations.

◆ distanceObstacles()

const ObjectStdVector_t& hpp::core::ProblemSolver::distanceObstacles ( ) const

Local vector of objects considered for distance computation.

◆ distanceType() [1/2]

void hpp::core::ProblemSolver::distanceType ( const std::string &  type)

Set distance type.

◆ distanceType() [2/2]

const std::string& hpp::core::ProblemSolver::distanceType ( ) const
inline

◆ erasePath()

void hpp::core::ProblemSolver::erasePath ( std::size_t  pathId)
inline

Erase a path.

◆ errorThreshold() [1/2]

void hpp::core::ProblemSolver::errorThreshold ( const value_type threshold)

Set error threshold in config projector.

◆ errorThreshold() [2/2]

value_type hpp::core::ProblemSolver::errorThreshold ( ) const
inline

Get errorimal number of threshold in config projector.

◆ executeOneStep()

virtual bool hpp::core::ProblemSolver::executeOneStep ( )
virtual

Execute one step of the planner.

Returns
the return value of PathPlanner::pathExists of the selected planner.
Note
This won't check if a solution has been found before doing one step. The decision to stop planning is let to the user.

◆ filterCollisionPairs()

void hpp::core::ProblemSolver::filterCollisionPairs ( )

Build matrix of relative motions between joints

Call Problem::filterCollisionPairs.

◆ finishSolveStepByStep()

virtual void hpp::core::ProblemSolver::finishSolveStepByStep ( )
virtual

Finish the solving procedure The path optimizer is not called

◆ getTimeOutPathPlanning()

double hpp::core::ProblemSolver::getTimeOutPathPlanning ( )
inline

set time out for the path planning ( in seconds)

◆ goalConfigs()

const Configurations_t& hpp::core::ProblemSolver::goalConfigs ( ) const

Get number of goal configuration.

◆ initConfig() [1/2]

const ConfigurationPtr_t& hpp::core::ProblemSolver::initConfig ( ) const
inline

Get shared pointer to initial configuration.

◆ initConfig() [2/2]

virtual void hpp::core::ProblemSolver::initConfig ( const ConfigurationPtr_t config)
virtual

Set initial configuration.

◆ initConfigValidation()

void hpp::core::ProblemSolver::initConfigValidation ( )

Set config validation by calling config validation factories.

◆ initDistance()

void hpp::core::ProblemSolver::initDistance ( )

Initialize distance

Set distance by calling the distance factory

◆ initializeProblem()

virtual void hpp::core::ProblemSolver::initializeProblem ( ProblemPtr_t  problem)
protectedvirtual

Initialize the new problem

Parameters
problemis inserted in the ProblemSolver and initialized.
Note
The previous Problem, if any, is not deleted. The function should be called when creating Problem object, in resetProblem() and all reimplementation in inherited class.

◆ initPathProjector()

void hpp::core::ProblemSolver::initPathProjector ( )

Initialize path projector

Set path projector by calling path projector factory

◆ initPathValidation()

void hpp::core::ProblemSolver::initPathValidation ( )

Set path validation by calling path validation factory.

◆ initProblemTarget()

virtual void hpp::core::ProblemSolver::initProblemTarget ( )
virtual

Initialize the problem target by calling the path validation factory.

◆ initSteeringMethod()

void hpp::core::ProblemSolver::initSteeringMethod ( )

Initialize steering method

Set steering method by calling the steering method factory

◆ initValidations()

void hpp::core::ProblemSolver::initValidations ( )

Initialize the config and path validations and add the obstacles.

◆ interrupt()

void hpp::core::ProblemSolver::interrupt ( )

Interrupt path planning and path optimization.

◆ maxIterPathPlanning() [1/2]

void hpp::core::ProblemSolver::maxIterPathPlanning ( size_type  iterations)

Set maximal number of iterations in config projector.

◆ maxIterPathPlanning() [2/2]

size_type hpp::core::ProblemSolver::maxIterPathPlanning ( ) const
inline

Get maximal number of iterations in config projector.

◆ maxIterProjection() [1/2]

void hpp::core::ProblemSolver::maxIterProjection ( size_type  iterations)

Set maximal number of iterations in config projector.

◆ maxIterProjection() [2/2]

size_type hpp::core::ProblemSolver::maxIterProjection ( ) const
inline

Get maximal number of iterations in config projector.

◆ numericalConstraint()

constraints::ImplicitPtr_t hpp::core::ProblemSolver::numericalConstraint ( const std::string &  name)
inline

Get constraint with given name.

◆ obstacle()

CollisionObjectPtr_t hpp::core::ProblemSolver::obstacle ( const std::string &  name) const

Get obstacle by name Throws if obstacle does not exists.

◆ obstacleFramePosition()

const Transform3f& hpp::core::ProblemSolver::obstacleFramePosition ( const std::string &  name) const

Get obstacle frame position by name Throws if obstacle frame does not exists.

◆ obstacleGeomData()

pinocchio::GeomDataPtr_t hpp::core::ProblemSolver::obstacleGeomData ( ) const
inline

◆ obstacleGeomModel()

pinocchio::GeomModelPtr_t hpp::core::ProblemSolver::obstacleGeomModel ( ) const
inline

◆ obstacleNames()

std::list<std::string> hpp::core::ProblemSolver::obstacleNames ( bool  collision,
bool  distance 
) const

Get list of obstacle names

Parameters
collisionwhether to return collision obstacle names
distancewhether to return distance obstacle names
Returns
list of obstacle names

◆ optimizePath()

void hpp::core::ProblemSolver::optimizePath ( PathVectorPtr_t  path)

Optimize path

Parameters
pathpath to optimize Build vector of path optimizers if needed
Note
each intermediate optimization output is stored in this object.

◆ pathOptimizer()

const PathOptimizerPtr_t& hpp::core::ProblemSolver::pathOptimizer ( std::size_t  rank) const
inline

Get path optimizer at given rank.

◆ pathOptimizerTypes()

const PathOptimizerTypes_t& hpp::core::ProblemSolver::pathOptimizerTypes ( ) const
inline

◆ pathPlanner()

const PathPlannerPtr_t& hpp::core::ProblemSolver::pathPlanner ( ) const
inline

Get path planner.

◆ pathPlannerType() [1/2]

virtual void hpp::core::ProblemSolver::pathPlannerType ( const std::string &  type)
virtual

Set path planner type.

◆ pathPlannerType() [2/2]

const std::string& hpp::core::ProblemSolver::pathPlannerType ( ) const
inline

◆ pathProjectorType() [1/2]

void hpp::core::ProblemSolver::pathProjectorType ( const std::string &  type,
const value_type step 
)

Set path projector method

Parameters
typename of new path validation method
stepdiscontinuity tolerance

◆ pathProjectorType() [2/2]

const std::string& hpp::core::ProblemSolver::pathProjectorType ( value_type tolerance) const
inline

Get path projector current type and get tolerance.

◆ paths()

const PathVectors_t& hpp::core::ProblemSolver::paths ( ) const
inline

Return vector of paths.

◆ pathValidationType() [1/2]

virtual void hpp::core::ProblemSolver::pathValidationType ( const std::string &  type,
const value_type tolerance 
)
virtual

Set path validation method

Parameters
typename of new path validation method
toleranceacceptable penetration for path validation Path validation methods are used to validate edges in path planning path optimization methods.

◆ pathValidationType() [2/2]

const std::string& hpp::core::ProblemSolver::pathValidationType ( value_type tolerance) const
inline

◆ prepareSolveStepByStep()

virtual bool hpp::core::ProblemSolver::prepareSolveStepByStep ( )
virtual

Prepare the solver for a step by step planning. and try to make direct connections (call PathPlanner::tryDirectPath)

Returns
the return value of PathPlanner::pathExists

◆ problem() [1/2]

ProblemPtr_t hpp::core::ProblemSolver::problem ( )
inline

Get pointer to problem.

◆ problem() [2/2]

void hpp::core::ProblemSolver::problem ( ProblemPtr_t  problem)
protected

Set pointer to problem.

◆ removeObstacle()

virtual void hpp::core::ProblemSolver::removeObstacle ( const std::string &  name)
virtual

Remove obstacle from the list.

Parameters
namename of the obstacle

◆ removeObstacleFromJoint()

void hpp::core::ProblemSolver::removeObstacleFromJoint ( const std::string &  jointName,
const std::string &  obstacleName 
)

Remove collision pair between a joint and an obstacle

Parameters
jointNamename of the joint,
obstacleNamename of the obstacle

◆ resetConstraints()

virtual void hpp::core::ProblemSolver::resetConstraints ( )
virtual

Reset constraint set.

◆ resetGoalConfigs()

void hpp::core::ProblemSolver::resetGoalConfigs ( )

Reset the set of goal configurations.

◆ resetProblem()

virtual void hpp::core::ProblemSolver::resetProblem ( )
virtual

Create new problem.

◆ resetRoadmap()

virtual void hpp::core::ProblemSolver::resetRoadmap ( )
virtual

Reset the roadmap.

Note
When joints bounds are changed, the roadmap must be reset because the kd tree must be resized.

◆ roadmap() [1/2]

const RoadmapPtr_t& hpp::core::ProblemSolver::roadmap ( ) const
inline

◆ roadmap() [2/2]

void hpp::core::ProblemSolver::roadmap ( const RoadmapPtr_t roadmap)
inline

Set the roadmap.

◆ robot() [1/2]

virtual void hpp::core::ProblemSolver::robot ( const DevicePtr_t robot)
virtual

Set robot.

◆ robot() [2/2]

const DevicePtr_t& hpp::core::ProblemSolver::robot ( ) const

Get robot.

◆ robotType() [1/2]

void hpp::core::ProblemSolver::robotType ( const std::string &  type)

Set robot type

Parameters
typetype of the robots that will be created later

◆ robotType() [2/2]

const std::string& hpp::core::ProblemSolver::robotType ( ) const

Get robot type.

◆ setTimeOutPathPlanning()

void hpp::core::ProblemSolver::setTimeOutPathPlanning ( double  timeOut)
inline

set time out for the path planning ( in seconds)

◆ solve()

virtual void hpp::core::ProblemSolver::solve ( )
virtual

Set and solve the problem.

◆ steeringMethodType() [1/2]

void hpp::core::ProblemSolver::steeringMethodType ( const std::string &  type)

Set steering method type.

◆ steeringMethodType() [2/2]

const std::string& hpp::core::ProblemSolver::steeringMethodType ( ) const
inline

Member Data Documentation

◆ affordanceConfigs

Container<AffordanceConfig_t> hpp::core::ProblemSolver::affordanceConfigs

Container of AffordanceConfig_t.

◆ affordanceObjects

Container<AffordanceObjects_t> hpp::core::ProblemSolver::affordanceObjects

Container of AffordanceObjects_t.

◆ centerOfMassComputations

Container<CenterOfMassComputationPtr_t> hpp::core::ProblemSolver::centerOfMassComputations

Container of CenterOfMassComputation.

◆ configurationShooters

Container<ConfigurationShooterBuilder_t> hpp::core::ProblemSolver::configurationShooters

Container of static method that creates a ConfigurationShooter with a robot as input

◆ configValidations

Container<ConfigValidationBuilder_t> hpp::core::ProblemSolver::configValidations

Container of static method that creates a ConfigValidation with a robot as input.

◆ constraints_

ConstraintSetPtr_t hpp::core::ProblemSolver::constraints_
protected

Store constraints until call to solve.

◆ distances

Container<DistanceBuilder_t> hpp::core::ProblemSolver::distances

Container of static method that creates a Distance with problem as input

◆ jointAndShapes

Container<JointAndShapes_t> hpp::core::ProblemSolver::jointAndShapes

Container of JointAndShapes_t.

◆ lockedJoints

member lockedJoints has been removed. LockedJointPtr_t instances are now stored with constraints::ImplicitPtr_t in member numericalConstraints.

◆ numericalConstraints

Container<constraints::ImplicitPtr_t> hpp::core::ProblemSolver::numericalConstraints

◆ passiveDofs

Container<segments_t> hpp::core::ProblemSolver::passiveDofs

Container of passive DoFs (as segments_t)

◆ pathOptimizers

Container<PathOptimizerBuilder_t> hpp::core::ProblemSolver::pathOptimizers

Container of static method that creates a PathOptimizer with a problem as input

◆ pathPlanner_

PathPlannerPtr_t hpp::core::ProblemSolver::pathPlanner_
protected

◆ pathPlanners

Container<PathPlannerBuilder_t> hpp::core::ProblemSolver::pathPlanners

Container of static method that creates a PathPlanner with a problem and a roadmap as input

◆ pathPlannerType_

std::string hpp::core::ProblemSolver::pathPlannerType_
protected

Path planner.

◆ pathProjectors

Container<PathProjectorBuilder_t> hpp::core::ProblemSolver::pathProjectors

Container of static method that creates a PathProjection with a problem and a tolerance as input.

◆ pathProjectorTolerance_

value_type hpp::core::ProblemSolver::pathProjectorTolerance_
protected

Tolerance of path projector.

◆ pathProjectorType_

std::string hpp::core::ProblemSolver::pathProjectorType_
protected

Path projector method.

◆ paths_

PathVectors_t hpp::core::ProblemSolver::paths_
protected

Paths.

◆ pathValidations

Container<PathValidationBuilder_t> hpp::core::ProblemSolver::pathValidations

Container of static method that creates a PathValidation with a robot and a tolerance as input.

◆ problem_

ProblemPtr_t hpp::core::ProblemSolver::problem_
protected

◆ roadmap_

RoadmapPtr_t hpp::core::ProblemSolver::roadmap_
protected

Store roadmap.

◆ robot_

DevicePtr_t hpp::core::ProblemSolver::robot_
protected

Robot.

◆ robots

Container<RobotBuilder_t> hpp::core::ProblemSolver::robots

Container of static method that creates a Robot with string as input

◆ steeringMethods

Container<SteeringMethodBuilder_t> hpp::core::ProblemSolver::steeringMethods

Container of static method that creates a SteeringMethod with a problem as input

◆ target_

ProblemTargetPtr_t hpp::core::ProblemSolver::target_
protected

Shared pointer to the problem target.


The documentation for this class was generated from the following file: