hpp-corbaserver  4.9.0
Corba server for Humanoid Path Planner applications
hpp.corbaserver.problem_solver.ProblemSolver Class Reference

Definition of a path planning problem. More...

Inheritance diagram for hpp.corbaserver.problem_solver.ProblemSolver:
Collaboration diagram for hpp.corbaserver.problem_solver.ProblemSolver:

Public Member Functions

def __init__ (self, robot, hppcorbaClient=None)
 
def loadPlugin (self, pluginName)
 Load a plugin into the current ProblemSolver. More...
 
def setRandomSeed (self, seed)
 Set random seed of random number generator. More...
 
def setMaxNumThreads (self, n)
 Set the maximum number of threads. More...
 
def getMaxNumThreads (self)
 Get the maximum number of concurrent access to the device (in thread safe areas). 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...
 
def setParameter (self, name, value)
 Set a parameter. More...
 
def getParameter (self, name, keep_any=False)
 Get parameter with given name raise an exception when the parameter is not found. More...
 
def getParameterDoc (self, name)
 Get parameter documentation raise an exception when the parameter is not found. More...
 
def selectProblem (self, name)
 
def movePathToProblem (self, pathId, problemName, jointNames)
 
Initial and goal configurations
def setInitialConfig (self, dofArray)
 Set initial configuration of specified problem. More...
 
def getInitialConfig (self)
 Get initial configuration of specified problem. More...
 
def addGoalConfig (self, dofArray)
 Add goal configuration to specified problem. More...
 
def getGoalConfigs (self)
 Get goal configurations of specified problem. More...
 
def resetGoalConfigs (self)
 Reset goal configurations. More...
 
Obstacles
def loadObstacleFromUrdf (self, args)
 Load obstacle from urdf file. More...
 
def removeObstacleFromJoint (self, objectName, jointName, collision, distance)
 Remove an obstacle from outer objects of a joint body. More...
 
def cutObstacle (self, objectName, aabb)
 Cut the obstacle with the given AABB. More...
 
def moveObstacle (self, objectName, cfg)
 Move an obstacle to a given configuration. More...
 
def getObstaclePosition (self, objectName)
 Get the position of an obstacle. More...
 
def getObstacleNames (self, collision, distance)
 Get list of obstacles. More...
 
def getObstacleLinkPosition (self, objectName)
 
def getObstacleLinkNames (self)
 Get list of obstacles. More...
 
Constraints
def createOrientationConstraint (self, constraintName, joint1Name, joint2Name, p, mask)
 Create orientation constraint between two joints. More...
 
def createTransformationConstraint (self, constraintName, joint1Name, joint2Name, ref, mask)
 Create transformation constraint between two joints. More...
 
def createLockedJoint (self, lockedDofName, jointName, value)
 Create a LockedJoint constraint with given value. More...
 
def createLockedExtraDof (self, lockedDofName, index, value)
 Create a locked extradof hpp::manipulation::ProblemSolver map. More...
 
def createRelativeComConstraint (self, constraintName, comName, jointLName, point, mask)
 Create RelativeCom constraint between two joints. More...
 
def createComBeetweenFeet (self, constraintName, comName, jointLName, jointRName, pointL, pointR, jointRefName, mask)
 Create ComBeetweenFeet constraint between two joints. More...
 
def addPartialCom (self, comName, jointNames)
 Add an object to compute a partial COM of the robot. More...
 
def getPartialCom (self, comName)
 
def createPositionConstraint (self, constraintName, joint1Name, joint2Name, point1, point2, mask)
 Create position constraint between two joints. More...
 
def createDistanceBetweenJointConstraint (self, constraintName, joint1Name, joint2Name, distance)
 Create distance constraint between robot objects. More...
 
def createDistanceBetweenJointAndObjects (self, constraintName, joint1Name, objects, distance)
 Create distance constraint between robot and environment objects. More...
 
def resetConstraints (self)
 Reset Constraints. More...
 
def resetConstraintMap (self)
 Delete all the constraint in the ProblemSolver map. More...
 
def addNumericalConstraints (self, name, names, priorities=None)
 Add numerical constraints in ConfigProjector. More...
 
def addLockedJointConstraints (self, name, names)
 Add locked joint in ConfigProjector. More...
 
def setRightHandSide (self, rhs)
 Set right hand side of constraints in config projector. More...
 
def setRightHandSideByName (self, constraintName, rhs)
 Set right hand side of given constraint in config projector. More...
 
def setRightHandSideFromConfig (self, config)
 Set right hand side of constraints in config projector. More...
 
def setRightHandSideFromConfigByName (self, constraintName, config)
 Set right hand side of given constraint in config projector. More...
 
def applyConstraints (self, q)
 Apply constraints. More...
 
def optimize (self, q)
 Find a local minimum of the least priority constraints. More...
 
def computeValueAndJacobian (self, q)
 Compute value and Jacobian of numerical constraints. More...
 
def addPassiveDofs (self, name, dofNames)
 Create a vector of passive dofs. More...
 
def setConstantRightHandSide (self, constraintName, constant)
 (Dis-)Allow to modify right hand side of a numerical constraint More...
 
def getConstantRightHandSide (self, constraintName)
 Get whether right hand side of a numerical constraint is constant. More...
 
def generateValidConfig (self, maxIter)
 Generate a configuration satisfying the constraints. More...
 
def getErrorThreshold (self)
 error threshold in numerical constraint resolution More...
 
def setErrorThreshold (self, threshold)
 error threshold in numerical constraint resolution More...
 
def setDefaultLineSearchType (self, type)
 set the default line search type used in the projection. More...
 
def getMaxIterPathPlanning (self)
 Get the maximal number of iterations in projection. More...
 
def setMaxIterPathPlanning (self, iterations)
 Set the maximal number of iterations in projection. More...
 
def getTimeOutPathPlanning (self)
 Get time out in path planning (in seconds) More...
 
def setTimeOutPathPlanning (self, timeOut)
 Set time out in path planning (in seconds) More...
 
def getMaxIterProjection (self)
 Get the maximal number of iterations in projection. More...
 
def setMaxIterProjection (self, iterations)
 Set the maximal number of iterations in projection. More...
 
Collision Checking
def filterCollisionPairs (self)
 Build matrix of relative motions between joints. More...
 
Solve problem and get paths
def selectPathPlanner (self, pathPlannerType)
 Select path planner type. More...
 
def selectConfigurationShooter (self, configurationShooterType)
 Select configuration shooter type. More...
 
def addPathOptimizer (self, pathOptimizerType)
 Add a path optimizer. More...
 
def clearPathOptimizers (self)
 Clear sequence of path optimizers. More...
 
def selectPathValidation (self, pathValidationType, tolerance)
 Select path validation method. More...
 
def addConfigValidation (self, configValidationType)
 Add path validation object. More...
 
def selectConfigurationShooter (self, type)
 Select configuration shooter type. More...
 
def selectPathProjector (self, pathProjectorType, tolerance)
 Select path projector method. More...
 
def selectDistance (self, distanceType)
 Select distance type. More...
 
def selectSteeringMethod (self, steeringMethodType)
 Select steering method type. More...
 
def prepareSolveStepByStep (self)
 
def executeOneStep (self)
 
def finishSolveStepByStep (self)
 
def solve (self)
 Solve the problem of corresponding ChppPlanner object. More...
 
def directPath (self, startConfig, endConfig, validate)
 Make direct connection between two configurations. More...
 
def appendDirectPath (self, pathId, config, validate)
 Append a path to an existing path. More...
 
def concatenatePath (self, startId, endId)
 Concatenate path endId at the end of startId. More...
 
def extractPath (self, pathId, start, end)
 extract path pathId from param start to end More...
 
def erasePath (self, pathId)
 Erase path pathId from stored. More...
 
def projectPath (self, pathId)
 Project path using the path projector. More...
 
def numberPaths (self)
 Get Number of paths. More...
 
def optimizePath (self, inPathId)
 Optimize a given path. More...
 
def pathLength (self, inPathId)
 Get length of path. More...
 
def configAtParam (self, inPathId, param)
 Get the robot config at param on a path. More...
 
def derivativeAtParam (self, inPathId, order, param)
 Get the robot velocity at param on a path. More...
 
def getWaypoints (self, pathId)
 Get way points of a path. More...
 
Interruption of a path planning request
def interruptPathPlanning (self)
 Interrupt path planning activity. More...
 
exploring the roadmap
def nodes (self)
 Get nodes of the roadmap. More...
 
def node (self, nodeId)
 
def numberNodes (self)
 
def numberEdges (self)
 Number of edges. More...
 
def edge (self, edgeId)
 Edge at given rank. More...
 
def numberConnectedComponents (self)
 Number of connected components. More...
 
def nodesConnectedComponent (self, ccId)
 Nodes of a connected component. More...
 
def getNearestConfig (self, randomConfig, connectedComponentId=-1)
 Return nearest neighbour of given input configuration. More...
 
def addConfigToRoadmap (self, config)
 Add a configuration to the roadmap. More...
 
def addEdgeToRoadmap (self, config1, config2, pathId, bothEdges)
 Add an edge to roadmap. More...
 
def clearRoadmap (self)
 Clear the roadmap. More...
 
def saveRoadmap (self, filename)
 Save the current roadmap in a file. More...
 
def readRoadmap (self, filename)
 Read a roadmap from a file. More...
 

Public Attributes

 client
 
 hppcorba
 
 robot
 

Detailed Description

Definition of a path planning problem.

This class wraps the Corba client to the server implemented by libhpp-corbaserver.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 hpp.corbaserver.problem_solver.ProblemSolver.__init__ (   self,
  robot,
  hppcorbaClient = None 
)

Member Function Documentation

◆ addConfigToRoadmap()

def hpp.corbaserver.problem_solver.ProblemSolver.addConfigToRoadmap (   self,
  config 
)

Add a configuration to the roadmap.

Parameters
configto be added to the roadmap.

◆ addConfigValidation()

def hpp.corbaserver.problem_solver.ProblemSolver.addConfigValidation (   self,
  configValidationType 
)

Add path validation object.

Parameters
configValidationTypename of the config validation method

◆ addEdgeToRoadmap()

def hpp.corbaserver.problem_solver.ProblemSolver.addEdgeToRoadmap (   self,
  config1,
  config2,
  pathId,
  bothEdges 
)

Add an edge to roadmap.

If

Parameters
config1,config2the ends of the path,
pathIdthe index if the path in the vector of path,
bothEdgesif FALSE, only add config1 to config2, otherwise, If TRUE. add edges config1->config2 AND config2->config1.

◆ addGoalConfig()

def hpp.corbaserver.problem_solver.ProblemSolver.addGoalConfig (   self,
  dofArray 
)

Add goal configuration to specified problem.

Parameters
dofArrayArray of degrees of freedom
Exceptions
Error.

◆ addLockedJointConstraints()

def hpp.corbaserver.problem_solver.ProblemSolver.addLockedJointConstraints (   self,
  name,
  names 
)

Add locked joint in ConfigProjector.

Parameters
namename of the config projector created if any,
nameslist of names of the locked joints previously created by method createLockedJoint.

◆ addNumericalConstraints()

def hpp.corbaserver.problem_solver.ProblemSolver.addNumericalConstraints (   self,
  name,
  names,
  priorities = None 
)

Add numerical constraints in ConfigProjector.

Parameters
namename of the config projector created if any,
nameslist of names of the numerical constraints previously created by methods createTransformationConstraint, createRelativeComConstraint, ...

◆ addPartialCom()

def hpp.corbaserver.problem_solver.ProblemSolver.addPartialCom (   self,
  comName,
  jointNames 
)

Add an object to compute a partial COM of the robot.

Parameters
nameof the partial com
jointNameslist of joint name of each tree ROOT to consider.
Note
Joints are added recursively, it is not possible so far to add a joint without addind all its children.

◆ addPassiveDofs()

def hpp.corbaserver.problem_solver.ProblemSolver.addPassiveDofs (   self,
  name,
  dofNames 
)

Create a vector of passive dofs.

Parameters
namename of the vector in the ProblemSolver map.
dofNameslist of names of DOF that may

◆ addPathOptimizer()

def hpp.corbaserver.problem_solver.ProblemSolver.addPathOptimizer (   self,
  pathOptimizerType 
)

Add a path optimizer.

Parameters
Nameof the path optimizer type, either "RandomShortcut" or any type added by core::ProblemSolver::addPathOptimizerType

◆ appendDirectPath()

def hpp.corbaserver.problem_solver.ProblemSolver.appendDirectPath (   self,
  pathId,
  config,
  validate 
)

Append a path to an existing path.

Parameters
pathIdId of the path in this problem,
configend configuration of the new path.
Exceptions
Errorif steering method fails to create a direct path of if direct path is not valid Call steering method between end of path and input config and append direct path in case of success.

◆ applyConstraints()

def hpp.corbaserver.problem_solver.ProblemSolver.applyConstraints (   self,
  q 
)

Apply constraints.

Parameters
qinitial configuration
Returns
configuration projected in success,
Exceptions
Errorif projection failed.

◆ clearPathOptimizers()

def hpp.corbaserver.problem_solver.ProblemSolver.clearPathOptimizers (   self)

Clear sequence of path optimizers.

◆ clearRoadmap()

def hpp.corbaserver.problem_solver.ProblemSolver.clearRoadmap (   self)

Clear the roadmap.

◆ computeValueAndJacobian()

def hpp.corbaserver.problem_solver.ProblemSolver.computeValueAndJacobian (   self,
  q 
)

Compute value and Jacobian of numerical constraints.

Parameters
qinput configuration
Returns
value values of the numerical constraints stacked in a unique vector,
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.

◆ concatenatePath()

def hpp.corbaserver.problem_solver.ProblemSolver.concatenatePath (   self,
  startId,
  endId 
)

Concatenate path endId at the end of startId.

Note
No path are created. The resulting path is at rank startId.

◆ configAtParam()

def hpp.corbaserver.problem_solver.ProblemSolver.configAtParam (   self,
  inPathId,
  param 
)

Get the robot config at param on a path.

Parameters
inPathIdrank of the path in the problem
param: the user parameter choice
Returns
dofseq : the config at param

◆ createComBeetweenFeet()

def hpp.corbaserver.problem_solver.ProblemSolver.createComBeetweenFeet (   self,
  constraintName,
  comName,
  jointLName,
  jointRName,
  pointL,
  pointR,
  jointRefName,
  mask 
)

Create ComBeetweenFeet constraint between two joints.

Parameters
constraintNamename of the constraint created,
comNamename of CenterOfMassComputation
jointLNamename of first joint
jointRNamename of second joint
pointLpoint in local frame of jointL.
pointRpoint in local frame of jointR.
jointRefNamename of second joint
maskSelect axis to be constrained. If jointRef is "", the robot root joint is used. Constraints are stored in ProblemSolver object

◆ createDistanceBetweenJointAndObjects()

def hpp.corbaserver.problem_solver.ProblemSolver.createDistanceBetweenJointAndObjects (   self,
  constraintName,
  joint1Name,
  objects,
  distance 
)

Create distance constraint between robot and environment objects.

Parameters
constraintNamename of the constraint created,
joint1Namename of first joint,
objectsnames of environment objects,
distancedesired distance between joint bodies. Constraints are stored in ProblemSolver object

◆ createDistanceBetweenJointConstraint()

def hpp.corbaserver.problem_solver.ProblemSolver.createDistanceBetweenJointConstraint (   self,
  constraintName,
  joint1Name,
  joint2Name,
  distance 
)

Create distance constraint between robot objects.

Parameters
constraintNamename of the constraint created,
joint1Namename of first joint,
joint2Namename of second joint,
distancedesired distance between joint bodies. Constraints are stored in ProblemSolver object

◆ createLockedExtraDof()

def hpp.corbaserver.problem_solver.ProblemSolver.createLockedExtraDof (   self,
  lockedDofName,
  index,
  value 
)

Create a locked extradof hpp::manipulation::ProblemSolver map.

Parameters
lockedDofNamekey of the constraint in the Problem Solver map
indexindex of the extra dof (0 means the first extra dof)
valuevalue of the extra dof configuration. The size of this vector defines the size of the constraints.

◆ createLockedJoint()

def hpp.corbaserver.problem_solver.ProblemSolver.createLockedJoint (   self,
  lockedDofName,
  jointName,
  value 
)

Create a LockedJoint constraint with given value.

Parameters
lockedJointNamekey of the constraint in the ProblemSolver map,
jointNamename of the joint,
valuevalue of the joint configuration,

◆ createOrientationConstraint()

def hpp.corbaserver.problem_solver.ProblemSolver.createOrientationConstraint (   self,
  constraintName,
  joint1Name,
  joint2Name,
  p,
  mask 
)

Create orientation constraint between two joints.

Parameters
constraintNamename of the constraint created,
joint1Namename of first joint
joint2Namename of second joint
pquaternion representing the desired orientation of joint2 in the frame of joint1.
maskSelect which axis to be constrained. If joint1 or joint2 is "", the corresponding joint is replaced by the global frame. constraints are stored in ProblemSolver object

◆ createPositionConstraint()

def hpp.corbaserver.problem_solver.ProblemSolver.createPositionConstraint (   self,
  constraintName,
  joint1Name,
  joint2Name,
  point1,
  point2,
  mask 
)

Create position constraint between two joints.

Parameters
constraintNamename of the constraint created,
joint1Namename of first joint
joint2Namename of second joint
point1point in local frame of joint1,
point2point in local frame of joint2.
maskSelect which axis to be constrained. If joint1 of joint2 is "", the corresponding joint is replaced by the global frame. constraints are stored in ProblemSolver object

◆ createRelativeComConstraint()

def hpp.corbaserver.problem_solver.ProblemSolver.createRelativeComConstraint (   self,
  constraintName,
  comName,
  jointLName,
  point,
  mask 
)

Create RelativeCom constraint between two joints.

Parameters
constraintNamename of the constraint created,
comNamename of CenterOfMassComputation
jointNamename of joint
pointpoint in local frame of joint.
maskSelect axis to be constrained. If jointName is "", the robot root joint is used. Constraints are stored in ProblemSolver object

◆ createTransformationConstraint()

def hpp.corbaserver.problem_solver.ProblemSolver.createTransformationConstraint (   self,
  constraintName,
  joint1Name,
  joint2Name,
  ref,
  mask 
)

Create transformation constraint between two joints.

Parameters
constraintNamename of the constraint created,
joint1Namename of first joint
joint2Namename of second joint
refdesired transformation of joint2 in the frame of joint1.
maskSelect which axis to be constrained. If joint1 of joint2 is "", the corresponding joint is replaced by the global frame. constraints are stored in ProblemSolver object

◆ cutObstacle()

def hpp.corbaserver.problem_solver.ProblemSolver.cutObstacle (   self,
  objectName,
  aabb 
)

Cut the obstacle with the given AABB.

Parameters
aabba vector of 6 floats. The 3 first represent one corner and the 3 last represent the opposite corner.

◆ derivativeAtParam()

def hpp.corbaserver.problem_solver.ProblemSolver.derivativeAtParam (   self,
  inPathId,
  order,
  param 
)

Get the robot velocity at param on a path.

Parameters
inPathIdrank of the path in the problem
orderIdorder of the derivative
param: the user parameter choice
Returns
dofseq : the velocity at param

◆ directPath()

def hpp.corbaserver.problem_solver.ProblemSolver.directPath (   self,
  startConfig,
  endConfig,
  validate 
)

Make direct connection between two configurations.

Parameters
startConfig,endConfigthe 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.
Returns
True if the path is fully valid, False otherwise.
the path index of the collision-free part from startConfig,
a message explaining the reason why the path is not valid if relevant

◆ edge()

def hpp.corbaserver.problem_solver.ProblemSolver.edge (   self,
  edgeId 
)

Edge at given rank.

◆ erasePath()

def hpp.corbaserver.problem_solver.ProblemSolver.erasePath (   self,
  pathId 
)

Erase path pathId from stored.

◆ executeOneStep()

def hpp.corbaserver.problem_solver.ProblemSolver.executeOneStep (   self)

◆ extractPath()

def hpp.corbaserver.problem_solver.ProblemSolver.extractPath (   self,
  pathId,
  start,
  end 
)

extract path pathId from param start to end

Note
a New path is added to problem-solver

◆ filterCollisionPairs()

def hpp.corbaserver.problem_solver.ProblemSolver.filterCollisionPairs (   self)

Build matrix of relative motions between joints.

See hpp::core::Problem::filterCollisionPairs.

◆ finishSolveStepByStep()

def hpp.corbaserver.problem_solver.ProblemSolver.finishSolveStepByStep (   self)

◆ generateValidConfig()

def hpp.corbaserver.problem_solver.ProblemSolver.generateValidConfig (   self,
  maxIter 
)

Generate a configuration satisfying the constraints.

Parameters
maxItermaximum number of tries,
Returns
configuration projected in success,
Exceptions
Errorif projection failed.

◆ getAvailable()

def hpp.corbaserver.problem_solver.ProblemSolver.getAvailable (   self,
  type 
)

Return a list of available elements of type type.

Parameters
typeenter "type" to know what types I know of. This is case insensitive.

◆ getConstantRightHandSide()

def hpp.corbaserver.problem_solver.ProblemSolver.getConstantRightHandSide (   self,
  constraintName 
)

Get whether right hand side of a numerical constraint is constant.

Parameters
constraintNameName of the numerical constraint,
Returns
whether right hand side is constant

◆ getErrorThreshold()

def hpp.corbaserver.problem_solver.ProblemSolver.getErrorThreshold (   self)

error threshold in numerical constraint resolution

◆ getGoalConfigs()

def hpp.corbaserver.problem_solver.ProblemSolver.getGoalConfigs (   self)

Get goal configurations of specified problem.

Returns
Array of degrees of freedom

◆ getInitialConfig()

def hpp.corbaserver.problem_solver.ProblemSolver.getInitialConfig (   self)

Get initial configuration of specified problem.

Returns
Array of degrees of freedom

◆ getMaxIterPathPlanning()

def hpp.corbaserver.problem_solver.ProblemSolver.getMaxIterPathPlanning (   self)

Get the maximal number of iterations in projection.

◆ getMaxIterProjection()

def hpp.corbaserver.problem_solver.ProblemSolver.getMaxIterProjection (   self)

Get the maximal number of iterations in projection.

◆ getMaxNumThreads()

def hpp.corbaserver.problem_solver.ProblemSolver.getMaxNumThreads (   self)

Get the maximum number of concurrent access to the device (in thread safe areas).

◆ getNearestConfig()

def hpp.corbaserver.problem_solver.ProblemSolver.getNearestConfig (   self,
  randomConfig,
  connectedComponentId = -1 
)

Return nearest neighbour of given input configuration.

Parameters
connectedComponentIdis the index of a connected component in the roadmap. If connectedComponentId is negative, function goes through all connected components looking for the nearest node (configuration).
distancereturns the one-dimensional distance between
configand computed nearest node (configuration).
See also
numberConnectedComponents

◆ getObstacleLinkNames()

def hpp.corbaserver.problem_solver.ProblemSolver.getObstacleLinkNames (   self)

Get list of obstacles.

Parameters
collisionwhether to return obstacle for collision,
distancewhether to return obstacles for distance computation
Returns
list of obstacles

◆ getObstacleLinkPosition()

def hpp.corbaserver.problem_solver.ProblemSolver.getObstacleLinkPosition (   self,
  objectName 
)

◆ getObstacleNames()

def hpp.corbaserver.problem_solver.ProblemSolver.getObstacleNames (   self,
  collision,
  distance 
)

Get list of obstacles.

Parameters
collisionwhether to return obstacle for collision,
distancewhether to return obstacles for distance computation
Returns
list of obstacles

◆ getObstaclePosition()

def hpp.corbaserver.problem_solver.ProblemSolver.getObstaclePosition (   self,
  objectName 
)

Get the position of an obstacle.

Parameters
objectNamename of the polyhedron.
Return values
cfgPosition of the obstacle.
Exceptions
Error.

◆ getParameter()

def hpp.corbaserver.problem_solver.ProblemSolver.getParameter (   self,
  name,
  keep_any = False 
)

Get parameter with given name raise an exception when the parameter is not found.

◆ getParameterDoc()

def hpp.corbaserver.problem_solver.ProblemSolver.getParameterDoc (   self,
  name 
)

Get parameter documentation raise an exception when the parameter is not found.

◆ getPartialCom()

def hpp.corbaserver.problem_solver.ProblemSolver.getPartialCom (   self,
  comName 
)

◆ getSelected()

def hpp.corbaserver.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.

◆ getTimeOutPathPlanning()

def hpp.corbaserver.problem_solver.ProblemSolver.getTimeOutPathPlanning (   self)

Get time out in path planning (in seconds)

◆ getWaypoints()

def hpp.corbaserver.problem_solver.ProblemSolver.getWaypoints (   self,
  pathId 
)

Get way points of a path.

Parameters
pathIdrank of the path in the problem

◆ interruptPathPlanning()

def hpp.corbaserver.problem_solver.ProblemSolver.interruptPathPlanning (   self)

Interrupt path planning activity.

Note
this method is effective only when multi-thread policy is used by CORBA server. See constructor of class Server for details.

◆ loadObstacleFromUrdf()

def hpp.corbaserver.problem_solver.ProblemSolver.loadObstacleFromUrdf (   self,
  args 
)

Load obstacle from urdf file.

Parameters
filenamename of the urdf file possibly including "package://"
prefixprefix added to object names in case the same file is loaded several times

The kinematic structure of the urdf file is ignored. Only the geometric objects are loaded as obstacles.

◆ loadPlugin()

def hpp.corbaserver.problem_solver.ProblemSolver.loadPlugin (   self,
  pluginName 
)

Load a plugin into the current ProblemSolver.

Parameters
pluginNameeither an absolute filename or a filename relative to <a_path_in_LD_LIBRARY_PATH>/hppPlugins.
Note
This is reset each time resetProblem is called.

◆ moveObstacle()

def hpp.corbaserver.problem_solver.ProblemSolver.moveObstacle (   self,
  objectName,
  cfg 
)

Move an obstacle to a given configuration.

Parameters
objectNamename of the polyhedron.
cfgthe configuration of the obstacle.
Exceptions
Error.
Note
The obstacle is not added to local map impl::Obstacle::collisionListMap.
Build the collision entity of polyhedron for KCD.

◆ movePathToProblem()

def hpp.corbaserver.problem_solver.ProblemSolver.movePathToProblem (   self,
  pathId,
  problemName,
  jointNames 
)

◆ node()

def hpp.corbaserver.problem_solver.ProblemSolver.node (   self,
  nodeId 
)

◆ nodes()

def hpp.corbaserver.problem_solver.ProblemSolver.nodes (   self)

Get nodes of the roadmap.

◆ nodesConnectedComponent()

def hpp.corbaserver.problem_solver.ProblemSolver.nodesConnectedComponent (   self,
  ccId 
)

Nodes of a connected component.

Parameters
connectedComponentIdindex of connected component in roadmap
Returns
list of nodes of the connected component.

◆ numberConnectedComponents()

def hpp.corbaserver.problem_solver.ProblemSolver.numberConnectedComponents (   self)

Number of connected components.

◆ numberEdges()

def hpp.corbaserver.problem_solver.ProblemSolver.numberEdges (   self)

Number of edges.

◆ numberNodes()

def hpp.corbaserver.problem_solver.ProblemSolver.numberNodes (   self)

◆ numberPaths()

def hpp.corbaserver.problem_solver.ProblemSolver.numberPaths (   self)

Get Number of paths.

◆ optimize()

def hpp.corbaserver.problem_solver.ProblemSolver.optimize (   self,
  q 
)

Find a local minimum of the least priority constraints.

while respecting the other priorities.

Parameters
inputinput configuration,
Returns
output output configuration,
residualError.

◆ optimizePath()

def hpp.corbaserver.problem_solver.ProblemSolver.optimizePath (   self,
  inPathId 
)

Optimize a given path.

Parameters
inPathIdId of the path in this problem.
Exceptions
Error.

◆ pathLength()

def hpp.corbaserver.problem_solver.ProblemSolver.pathLength (   self,
  inPathId 
)

Get length of path.

Parameters
inPathIdrank of the path in the problem
Returns
length of path if path exists.

◆ prepareSolveStepByStep()

def hpp.corbaserver.problem_solver.ProblemSolver.prepareSolveStepByStep (   self)

◆ projectPath()

def hpp.corbaserver.problem_solver.ProblemSolver.projectPath (   self,
  pathId 
)

Project path using the path projector.

Returns
True in case of success, False otherwise.

◆ readRoadmap()

def hpp.corbaserver.problem_solver.ProblemSolver.readRoadmap (   self,
  filename 
)

Read a roadmap from a file.

Parameters
filenamename of the file from which the roadmap is read.

◆ removeObstacleFromJoint()

def hpp.corbaserver.problem_solver.ProblemSolver.removeObstacleFromJoint (   self,
  objectName,
  jointName,
  collision,
  distance 
)

Remove an obstacle from outer objects of a joint body.

Parameters
objectNamename of the object to remove,
jointNamename of the joint owning the body,
collisionwhether collision with object should be computed,
distancewhether distance to object should be computed.
Exceptions
Error.

◆ resetConstraintMap()

def hpp.corbaserver.problem_solver.ProblemSolver.resetConstraintMap (   self)

Delete all the constraint in the ProblemSolver map.

It erases both the numerical and locked joint constraints This does not resetConstraints of the problem to be solved.

◆ resetConstraints()

def hpp.corbaserver.problem_solver.ProblemSolver.resetConstraints (   self)

Reset Constraints.

Reset all constraints, including numerical constraints and locked joints

◆ resetGoalConfigs()

def hpp.corbaserver.problem_solver.ProblemSolver.resetGoalConfigs (   self)

Reset goal configurations.

◆ saveRoadmap()

def hpp.corbaserver.problem_solver.ProblemSolver.saveRoadmap (   self,
  filename 
)

Save the current roadmap in a file.

Parameters
filenamename of the file where the roadmap is saved

◆ selectConfigurationShooter() [1/2]

def hpp.corbaserver.problem_solver.ProblemSolver.selectConfigurationShooter (   self,
  configurationShooterType 
)

Select configuration shooter type.

Parameters
Nameof the configuration shooter type
Note
the configuration shooter is created and initialized when calling this method. This might be important if the initialization depends on the current state of the robot.

◆ selectConfigurationShooter() [2/2]

def hpp.corbaserver.problem_solver.ProblemSolver.selectConfigurationShooter (   self,
  type 
)

Select configuration shooter type.

Parameters
Nameof the configuration shooter type

◆ selectDistance()

def hpp.corbaserver.problem_solver.ProblemSolver.selectDistance (   self,
  distanceType 
)

Select distance type.

Parameters
Nameof the distance type, either "WeighedDistance" or any type added by method core::ProblemSolver::addDistanceType

◆ selectPathPlanner()

def hpp.corbaserver.problem_solver.ProblemSolver.selectPathPlanner (   self,
  pathPlannerType 
)

Select path planner type.

Parameters
Nameof the path planner type, either "DiffusingPlanner", "VisibilityPrmPlanner", or any type added by method core::ProblemSolver::addPathPlannerType

◆ selectPathProjector()

def hpp.corbaserver.problem_solver.ProblemSolver.selectPathProjector (   self,
  pathProjectorType,
  tolerance 
)

Select path projector method.

Parameters
Nameof the path projector method, either "Discretized" "Progressive", "Dichotomy", or any type added by core::ProblemSolver::addPathProjectorType,
tolerancemaximal acceptable penetration.

◆ selectPathValidation()

def hpp.corbaserver.problem_solver.ProblemSolver.selectPathValidation (   self,
  pathValidationType,
  tolerance 
)

Select path validation method.

Parameters
Nameof the path validation method, either "Discretized" "Progressive", "Dichotomy", or any type added by core::ProblemSolver::addPathValidationType,
tolerancemaximal acceptable penetration.

◆ selectProblem()

def hpp.corbaserver.problem_solver.ProblemSolver.selectProblem (   self,
  name 
)

◆ selectSteeringMethod()

def hpp.corbaserver.problem_solver.ProblemSolver.selectSteeringMethod (   self,
  steeringMethodType 
)

Select steering method type.

Parameters
Nameof the steering method type, either "SteeringMethodStraight" or any type added by method core::ProblemSolver::addSteeringMethodType

◆ setConstantRightHandSide()

def hpp.corbaserver.problem_solver.ProblemSolver.setConstantRightHandSide (   self,
  constraintName,
  constant 
)

(Dis-)Allow to modify right hand side of a numerical constraint

Parameters
constraintNameName of the numerical constraint,
constantwhether right hand side is constant

Constraints should have been added in the ProblemSolver local map, but not inserted in the config projector.

◆ setDefaultLineSearchType()

def hpp.corbaserver.problem_solver.ProblemSolver.setDefaultLineSearchType (   self,
  type 
)

set the default line search type used in the projection.

Parameters
Seehpp::core::ConfigProjector::LineSearchType for possible values.

◆ setErrorThreshold()

def hpp.corbaserver.problem_solver.ProblemSolver.setErrorThreshold (   self,
  threshold 
)

error threshold in numerical constraint resolution

◆ setInitialConfig()

def hpp.corbaserver.problem_solver.ProblemSolver.setInitialConfig (   self,
  dofArray 
)

Set initial configuration of specified problem.

Parameters
dofArrayArray of degrees of freedom
Exceptions
Error.

◆ setMaxIterPathPlanning()

def hpp.corbaserver.problem_solver.ProblemSolver.setMaxIterPathPlanning (   self,
  iterations 
)

Set the maximal number of iterations in projection.

◆ setMaxIterProjection()

def hpp.corbaserver.problem_solver.ProblemSolver.setMaxIterProjection (   self,
  iterations 
)

Set the maximal number of iterations in projection.

◆ setMaxNumThreads()

def hpp.corbaserver.problem_solver.ProblemSolver.setMaxNumThreads (   self,
  n 
)

Set the maximum number of threads.

This parameter defines the number of possible concurrent access to the device.

◆ setParameter()

def hpp.corbaserver.problem_solver.ProblemSolver.setParameter (   self,
  name,
  value 
)

Set a parameter.

Parameters
valuethe input type must be long, double, const char*
import CORBA
ProblemSolver ps(robot)
ps.setParameter ("name", CORBA.Any(CORBA.TC_double, 3.2233))

◆ setRandomSeed()

def hpp.corbaserver.problem_solver.ProblemSolver.setRandomSeed (   self,
  seed 
)

Set random seed of random number generator.

◆ setRightHandSide()

def hpp.corbaserver.problem_solver.ProblemSolver.setRightHandSide (   self,
  rhs 
)

Set right hand side of constraints in config projector.

Parameters
rhsright hand side of constraints. Contains only right hand side of non-constant constraints
Note
Locked joints are also considered.

◆ setRightHandSideByName()

def hpp.corbaserver.problem_solver.ProblemSolver.setRightHandSideByName (   self,
  constraintName,
  rhs 
)

Set right hand side of given constraint in config projector.

Parameters
constraintNamename of the numerical constraint or locked joint
rhsright hand side of constraint. raises an exception if constraint has constant right hand side.

◆ setRightHandSideFromConfig()

def hpp.corbaserver.problem_solver.ProblemSolver.setRightHandSideFromConfig (   self,
  config 
)

Set right hand side of constraints in config projector.

Parameters
configa robot configuration use to compute the right hand side of constraints. Contains only right hand side of non-constant constraints
Note
Locked joints are also considered.

◆ setRightHandSideFromConfigByName()

def hpp.corbaserver.problem_solver.ProblemSolver.setRightHandSideFromConfigByName (   self,
  constraintName,
  config 
)

Set right hand side of given constraint in config projector.

Parameters
constraintNamename of the numerical constraint or locked joint
configa robot configuration use to compute the right hand side. raises an exception if constraint has constant right hand side.

◆ setTimeOutPathPlanning()

def hpp.corbaserver.problem_solver.ProblemSolver.setTimeOutPathPlanning (   self,
  timeOut 
)

Set time out in path planning (in seconds)

◆ solve()

def hpp.corbaserver.problem_solver.ProblemSolver.solve (   self)

Solve the problem of corresponding ChppPlanner object.

Member Data Documentation

◆ client

hpp.corbaserver.problem_solver.ProblemSolver.client

◆ hppcorba

hpp.corbaserver.problem_solver.ProblemSolver.hppcorba

◆ robot

hpp.corbaserver.problem_solver.ProblemSolver.robot

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