manipulation.problem_solver.ProblemSolver Class Reference

Definition of a manipulation planning problem. More...

Inheritance diagram for manipulation.problem_solver.ProblemSolver:
[legend]
Collaboration diagram for manipulation.problem_solver.ProblemSolver:
[legend]

Public Member Functions

def __init__ (self, robot)
 
def selectProblem (self, name)
 Select a problem by its name. More...
 
def getAvailable (self, type)
 Return a list of available elements of type type. More...
 
def getSelected (self, type)
 Return a list of selected elements of type type. More...
 
Constraints
def createPlacementConstraints (self, placementName, shapeName, envContactName, width=0.05)
 Create placement and pre-placement constraints. More...
 
def balanceConstraints (self)
 Return balance constraints created by method ProblemSolver.createStaticStabilityConstraints. More...
 
def getConstantRightHandSide (self, constraintName)
 Get whether right hand side of a numerical constraint is constant. More...
 
def lockFreeFlyerJoint (self, freeflyerBname, lockJointBname, values=(0, 0, 0, 0, 0, 0, 1))
 Lock degree of freedom of a FreeFlyer joint. More...
 
def lockPlanarJoint (self, jointName, lockJointName, values=(0, 0, 1, 0))
 Lock degree of freedom of a planar joint. More...
 
Solve problem and get paths
def setTargetState (self, stateId)
 Set the problem target to stateId The planner will look for a path from the init configuration to a configuration in state stateId. More...
 

Detailed Description

Definition of a manipulation planning problem.

This class wraps the Corba client to the server implemented by libhpp-manipulation-corba.so

Some method implemented by the server can be considered as private. The goal of this class is to hide them and to expose those that can be considered as public.

Constructor & Destructor Documentation

◆ __init__()

def manipulation.problem_solver.ProblemSolver.__init__ (   self,
  robot 
)

Member Function Documentation

◆ balanceConstraints()

def manipulation.problem_solver.ProblemSolver.balanceConstraints (   self)

Return balance constraints created by method ProblemSolver.createStaticStabilityConstraints.

◆ createPlacementConstraints()

def manipulation.problem_solver.ProblemSolver.createPlacementConstraints (   self,
  placementName,
  shapeName,
  envContactName,
  width = 0.05 
)

◆ getAvailable()

def manipulation.problem_solver.ProblemSolver.getAvailable (   self,
  type 
)

◆ getConstantRightHandSide()

◆ getSelected()

def manipulation.problem_solver.ProblemSolver.getSelected (   self,
  type 
)

Return a list of selected elements of type type.

Parameters
typeenter "type" to know what types I know of. This is case insensitive.
Note
For most of the types, the list will contain only one element.

References hpp::corbaserver::benchmark::Benchmark.client, hpp::corbaserver::robot::Robot.client, hpp::corbaserver::problem_solver::ProblemSolver.client, manipulation.constraint_graph.ConstraintGraph.client, and hpp::corbaserver::problem_solver::ProblemSolver.getSelected().

◆ lockFreeFlyerJoint()

def manipulation.problem_solver.ProblemSolver.lockFreeFlyerJoint (   self,
  freeflyerBname,
  lockJointBname,
  values = (0,0,0,0,0,0,1) 
)

Lock degree of freedom of a FreeFlyer joint.

Parameters
freeflyerBnamebase name of the joint (It will be completed by '_xyz' and '_SO3'),
lockJointBnamebase name of the LockedJoint constraints (It will be completed by '_xyz' and '_SO3'),
valuesconfig of the locked joints (7 float)

References _impl_Problem.createLockedJoint(), hpp::corbaserver::problem_solver::ProblemSolver.createLockedJoint(), hpp::corbaserver::Problem.createLockedJoint(), hpp::corbaServer::impl::Problem.createLockedJoint(), and _objref_Problem.createLockedJoint().

◆ lockPlanarJoint()

def manipulation.problem_solver.ProblemSolver.lockPlanarJoint (   self,
  jointName,
  lockJointName,
  values = (0,0,1,0) 
)

Lock degree of freedom of a planar joint.

Parameters
jointNamename of the joint (It will be completed by '_xy' and '_rz'),
lockJointNamename of the LockedJoint constraint
valuesconfig of the locked joints (4 float)

References _impl_Problem.createLockedJoint(), hpp::corbaserver::problem_solver::ProblemSolver.createLockedJoint(), hpp::corbaserver::Problem.createLockedJoint(), hpp::corbaServer::impl::Problem.createLockedJoint(), and _objref_Problem.createLockedJoint().

◆ selectProblem()

def manipulation.problem_solver.ProblemSolver.selectProblem (   self,
  name 
)

Select a problem by its name.

If no problem with this name exists, a new hpp::manipulation::ProblemSolver is created and selected.

Parameters
namethe problem name.
Returns
true if a new problem was created.

References hpp::corbaserver::benchmark::Benchmark.client, hpp::corbaserver::robot::Robot.client, hpp::corbaserver::problem_solver::ProblemSolver.client, manipulation.constraint_graph.ConstraintGraph.client, and hpp::corbaserver::problem_solver::ProblemSolver.selectProblem().

◆ setTargetState()

def manipulation.problem_solver.ProblemSolver.setTargetState (   self,
  stateId 
)

Set the problem target to stateId The planner will look for a path from the init configuration to a configuration in state stateId.

References hpp::corbaserver::benchmark::Benchmark.client, hpp::corbaserver::problem_solver::ProblemSolver.client, hpp::corbaserver::robot::Robot.client, and manipulation.constraint_graph.ConstraintGraph.client.