hpp-manipulation 7.0.0
Classes for manipulation planning.
Loading...
Searching...
No Matches
hpp::manipulation::ProblemSolver Class Reference

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

Inheritance diagram for hpp::manipulation::ProblemSolver:
Collaboration diagram for hpp::manipulation::ProblemSolver:

Public Types

typedef core::ProblemSolver parent_t
typedef std::vector< std::string > Names_t
Public Types inherited from hpp::core::ProblemSolver
typedef std::vector< PathOptimizers_t
typedef std::vector< std::string > PathOptimizerTypes_t
typedef std::vector< std::string > ConfigValidationTypes_t

Public Member Functions

virtual ~ProblemSolver ()
 Destructor.
 ProblemSolver ()
virtual void robot (const core::DevicePtr_t &robot)
const DevicePtr_trobot () const
 Get robot.
void createPlacementConstraint (const std::string &name, const Strings_t &surface1, const Strings_t &surface2, const value_type &margin=1e-4)
void createPrePlacementConstraint (const std::string &name, const Strings_t &surface1, const Strings_t &surface2, const value_type &width, const value_type &margin=1e-4)
void createGraspConstraint (const std::string &name, const std::string &gripper, const std::string &handle)
void createPreGraspConstraint (const std::string &name, const std::string &gripper, const std::string &handle)
virtual void pathValidationType (const std::string &type, const value_type &tolerance)
virtual void resetProblem ()
 Create a new problem.
virtual void resetRoadmap ()
 Create a new Roadmap.
ProblemPtr_t problem () const
 Get pointer to problem.
void setTargetState (const graph::StatePtr_t state)
Constraint graph
void constraintGraph (const std::string &graph)
 Set the constraint graph.
graph::GraphPtr_t constraintGraph () const
 Get the constraint graph.
void initConstraintGraph ()
 Should be called before any call on the graph is made.
Public Member Functions inherited from hpp::core::ProblemSolver
void robotType (const std::string &type)
const std::string & robotType () const
createRobot (const std::string &name)
const robot () const
problem ()
const initConfig () const
virtual void ConfigurationIn_t config)
const goalConfigs () const
virtual void ConfigurationIn_t config)
void resetGoalConfigs ()
void constraints)
void resetGoalConstraints ()
virtual void pathPlannerType (const std::string &type)
const std::string & pathPlannerType () const
void distanceType (const std::string &type)
const std::string & distanceType () const
void steeringMethodType (const std::string &type)
const std::string & steeringMethodType () const
void configurationShooterType (const std::string &type)
const std::string & configurationShooterType () const
const pathPlanner () const
void addPathOptimizer (const std::string &type)
const pathOptimizerTypes () const
void clearPathOptimizers ()
const pathOptimizer (std::size_t rank) const
void PathVectorPtr_t path)
const std::string & value_type &tolerance) const
void value_type &step)
const std::string & value_type &tolerance) const
virtual void addConfigValidation (const std::string &type)
const configValidationTypes ()
void clearConfigValidations ()
void ConfigValidationBuilder_t &builder)
const roadmap () const
const collisionObstacles () const
const distanceObstacles () const
void RoadmapPtr_t &roadmap)
void initDistance ()
void initSteeringMethod ()
void initPathProjector ()
void initPathValidation ()
void initConfigValidation ()
void initValidations ()
virtual void initProblemTarget ()
void ConstraintPtr_t &constraint)
const constraints () const
virtual void resetConstraints ()
virtual void addNumericalConstraintToConfigProjector (const std::string &configProjName, const std::string &constraintName, const std::size_t priority=0)
void constraints::ImplicitPtr_t &constraint)
void ComparisonTypes_t types)
void ComparisonType &type)
comparisonType (const std::string &name) const
numericalConstraint (const std::string &name)
void matrix_t &jacobian) const
void size_type iterations)
maxIterProjection () const
void size_type iterations)
maxIterPathPlanning () const
void timeOut)
double getTimeOutPathPlanning ()
void value_type &threshold)
errorThreshold () const
void createPathOptimizers ()
virtual bool prepareSolveStepByStep ()
virtual bool executeOneStep ()
virtual void finishSolveStepByStep ()
virtual void solve ()
bool ConfigurationIn_t end, bool validate, std::size_t &pathId, std::string &report)
void ConfigurationIn_t config)
void PathPtr_t &path)
void interrupt ()
std::size_t PathVectorPtr_t &path)
void erasePath (std::size_t pathId)
const paths () const
virtual void DevicePtr_t &device, bool collision, bool distance)
virtual void CollisionObjectPtr_t &inObject, bool collision, bool distance)
virtual void removeObstacle (const std::string &name)
virtual void Transform3s &pose, bool collision, bool distance)
virtual void FclCollisionObject &inObject, bool collision, bool distance)
void removeObstacleFromJoint (const std::string &jointName, const std::string &obstacleName)
void cutObstacle (const std::string &name, const coal::AABB &aabb)
void filterCollisionPairs ()
obstacle (const std::string &name) const
const obstacleFramePosition (const std::string &name) const
std::list< std::string > obstacleNames (bool collision, bool distance) const
const distanceBetweenObjects () const
obstacleGeomModel () const
obstacleGeomData () const
void ConstraintPtr_t &constraint)
const constraints () const
virtual void resetConstraints ()
virtual void addNumericalConstraintToConfigProjector (const std::string &configProjName, const std::string &constraintName, const std::size_t priority=0)
void constraints::ImplicitPtr_t &constraint)
void ComparisonTypes_t types)
void ComparisonType &type)
comparisonType (const std::string &name) const
numericalConstraint (const std::string &name)
void matrix_t &jacobian) const
void size_type iterations)
maxIterProjection () const
void size_type iterations)
maxIterPathPlanning () const
void timeOut)
double getTimeOutPathPlanning ()
void value_type &threshold)
errorThreshold () const
void createPathOptimizers ()
virtual bool prepareSolveStepByStep ()
virtual bool executeOneStep ()
virtual void finishSolveStepByStep ()
virtual void solve ()
bool ConfigurationIn_t end, bool validate, std::size_t &pathId, std::string &report)
void ConfigurationIn_t config)
void PathPtr_t &path)
void interrupt ()
std::size_t PathVectorPtr_t &path)
void erasePath (std::size_t pathId)
const paths () const
virtual void DevicePtr_t &device, bool collision, bool distance)
virtual void CollisionObjectPtr_t &inObject, bool collision, bool distance)
virtual void removeObstacle (const std::string &name)
virtual void Transform3s &pose, bool collision, bool distance)
virtual void FclCollisionObject &inObject, bool collision, bool distance)
void removeObstacleFromJoint (const std::string &jointName, const std::string &obstacleName)
void cutObstacle (const std::string &name, const coal::AABB &aabb)
void filterCollisionPairs ()
obstacle (const std::string &name) const
const obstacleFramePosition (const std::string &name) const
std::list< std::string > obstacleNames (bool collision, bool distance) const
const distanceBetweenObjects () const
obstacleGeomModel () const
obstacleGeomData () const

Static Public Member Functions

static ProblemSolverPtr_t create ()
Static Public Member Functions inherited from hpp::core::ProblemSolver
static create ()

Public Attributes

core::Container< graph::GraphPtr_tgraphs
ConstraintsAndComplements_t constraintsAndComplements
Public Attributes inherited from hpp::core::ProblemSolver
robots
configurationShooters
steeringMethods
distances
pathValidations
configValidations
pathProjectors
pathPlanners
pathOptimizers
numericalConstraints
lockedJoints
centerOfMassComputations
passiveDofs
jointAndShapes
affordanceObjects
affordanceConfigs

Protected Member Functions

virtual void initializeProblem (ProblemPtr_t problem)
Protected Member Functions inherited from hpp::core::ProblemSolver
 ProblemSolver ()
void ProblemPtr_t problem)

Additional Inherited Members

Protected Attributes inherited from hpp::core::ProblemSolver
constraints_
robot_
problem_
pathPlanner_
roadmap_
paths_
std::string pathProjectorType_
pathProjectorTolerance_
std::string pathPlannerType_
target_

Member Typedef Documentation

◆ Names_t

typedef std::vector<std::string> hpp::manipulation::ProblemSolver::Names_t

◆ parent_t

Constructor & Destructor Documentation

◆ ~ProblemSolver()

virtual hpp::manipulation::ProblemSolver::~ProblemSolver()
inlinevirtual

Destructor.

Reimplemented from hpp::core::ProblemSolver.

◆ ProblemSolver()

hpp::manipulation::ProblemSolver::ProblemSolver()

Member Function Documentation

◆ constraintGraph() [1/2]

graph::GraphPtr_t hpp::manipulation::ProblemSolver::constraintGraph()const

Get the constraint graph.

◆ constraintGraph() [2/2]

void hpp::manipulation::ProblemSolver::constraintGraph(const std::string &graph)

Set the constraint graph.

◆ create()

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

◆ createGraspConstraint()

void hpp::manipulation::ProblemSolver::createGraspConstraint(const std::string &name,
const std::string &gripper,
const std::string &handle )

Create the grasp constraint and its complement

Parameters
namename of the grasp constraint,
grippergripper's name
handlehandle's name

Two constraints are created:

  • "name" corresponds to the grasp constraint.
  • "name/complement" corresponds to the complement.

◆ createPlacementConstraint()

void hpp::manipulation::ProblemSolver::createPlacementConstraint(const std::string &name,
const Strings_t &surface1,
const Strings_t &surface2,
const value_type &margin = 1e-4 )

Create placement constraint

Parameters
namename of the placement constraint,
triangleNamename of the first list of triangles,
envContactNamename of the second list of triangles.
marginsee hpp::constraints::ConvexShapeContact::setNormalMargin

◆ createPreGraspConstraint()

void hpp::manipulation::ProblemSolver::createPreGraspConstraint(const std::string &name,
const std::string &gripper,
const std::string &handle )

Create pre-grasp constraint

Parameters
namename of the grasp constraint,
grippergripper's name
handlehandle's name

◆ createPrePlacementConstraint()

void hpp::manipulation::ProblemSolver::createPrePlacementConstraint(const std::string &name,
const Strings_t &surface1,
const Strings_t &surface2,
const value_type &width,
const value_type &margin = 1e-4 )

Create pre-placement constraint

Parameters
namename of the placement constraint,
triangleNamename of the first list of triangles,
envContactNamename of the second list of triangles.
widthapproaching distance.
marginsee hpp::constraints::ConvexShapeContact::setNormalMargin

◆ initConstraintGraph()

void hpp::manipulation::ProblemSolver::initConstraintGraph()

Should be called before any call on the graph is made.

◆ initializeProblem()

virtual void hpp::manipulation::ProblemSolver::initializeProblem(ProblemPtr_tproblem)
protectedvirtual

Reimplemented from hpp::core::ProblemSolver.

◆ pathValidationType()

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

Reimplemented from hpp::core::ProblemSolver.

◆ problem()

ProblemPtr_t hpp::manipulation::ProblemSolver::problem()const
inline

Get pointer to problem.

◆ resetProblem()

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

Create a new problem.

Reimplemented from hpp::core::ProblemSolver.

◆ resetRoadmap()

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

Create a new Roadmap.

Reimplemented from hpp::core::ProblemSolver.

◆ robot() [1/2]

const DevicePtr_t & hpp::manipulation::ProblemSolver::robot()const
inline

Get robot.

◆ robot() [2/2]

virtual void hpp::manipulation::ProblemSolver::robot(const core::DevicePtr_t &robot)
inlinevirtual

Set robot Check that robot is of type hpp::manipulation::Device

Reimplemented from hpp::core::ProblemSolver.

◆ setTargetState()

void hpp::manipulation::ProblemSolver::setTargetState(const graph::StatePtr_tstate)

Member Data Documentation

◆ constraintsAndComplements

ConstraintsAndComplements_t hpp::manipulation::ProblemSolver::constraintsAndComplements

◆ graphs

core::Container<graph::GraphPtr_t> hpp::manipulation::ProblemSolver::graphs

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