Public Member Functions | Public Attributes | Static Public Attributes | List of all members
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 setRandomSeed (self, seed)
 Set random seed of random number generator. More...
 
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...
 
def setParameter (self, name, value)
 Set a parameter. More...
 
def getParameter (self, name)
 Get parameter with given name raise an exception when the parameter is not found. More...
 
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, package, filename, prefix)
 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 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...
 
Constraints
def createStaticStabilityConstraints (self, constraintName, q0, comName="", type=None)
 Create static stability constraints. More...
 
def createComplementStaticStabilityConstraints (self, constraintName, q0)
 Create complement of static stability constraints. More...
 
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 createOrientationConstraint (self, constraintName, joint1Name, joint2Name, p, mask)
 Reset Constraints. More...
 
def createPositionConstraint (self, constraintName, joint1Name, joint2Name, point1, point2, mask)
 Create position constraint between two joints. More...
 
def createTransformationConstraint (self, constraintName, joint1Name, joint2Name, ref, mask)
 Create transformation constraint between two joints. 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)
 Get the position of a partial COM created with addPartialCom. More...
 
def getJacobianPartialCom (self, comName)
 Get the Jacobian of a partial COM created with addPartialCom. 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 resetConstraints (self)
 Reset Constraints. More...
 
def setNumericalConstraints (self, name, names, priorities=None)
 Set numerical constraints in ConfigProjector. More...
 
def setLockedJointConstraints (self, name, names)
 Set locked joint in ConfigProjector. More...
 
def applyConstraints (self, q)
 Apply constraints. More...
 
def generateValidConfig (self, maxIter)
 Generate a configuration satisfying the constraints. 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 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...
 
def getErrorThreshold (self)
 error threshold in numerical constraint resolution More...
 
def setErrorThreshold (self, threshold)
 error threshold in numerical constraint resolution More...
 
def getMaxIterations (self)
 Set the maximal number of iterations. More...
 
def setMaxIterations (self, iterations)
 Set the maximal number of iterations. More...
 
def getMaxIterations (self)
 Set the maximal number of iterations in projection. More...
 
def setMaxIterations (self, iterations)
 Set the maximal number of iterations in 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 getMaxIterProjection (self)
 Get the maximal number of iterations in projection. More...
 
def setMaxIterProjection (self, iterations)
 Set the maximal number of iterations in projection. More...
 
Solve problem and get paths
def selectPathPlanner (self, pathPlannerType)
 Select path planner type. More...
 
def addPathOptimizer (self, pathOptimizerType)
 Add path optimizer type. More...
 
def clearPathOptimizers (self)
 Clear path optimizers. More...
 
def addConfigValidation (self, configValidationType)
 Add a config validation. More...
 
def clearConfigValidations (self)
 Clear config validations. More...
 
def selectPathValidation (self, pathValidationType, tolerance)
 Select path validation method. 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 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, atDistance)
 Get the robot's config at param on the a path. More...
 
def getWaypoints (self, pathId)
 Get way points of a path. More...
 
def erasePath (self, pathId)
 Delete a path. More...
 
def concatenatePath (self, pathId1, pathId2)
 Concatenate two paths The function appends the second path to the first one and remove the second 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)
 Number of nodes. More...
 
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 clearRoadmap (self)
 Clear the roadmap. 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 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...
 

Public Attributes

 client
 
 robot
 
 balanceConstraints_
 

Static Public Attributes

 SLIDING = hpp.corbaserver.wholebody_step.Problem.SLIDING
 
 SLIDING_ALIGNED_COM = \
 
 FIXED_ON_THE_GROUND = \
 
 FIXED_ALIGNED_COM = \
 

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

◆ addConfigToRoadmap()

def manipulation.problem_solver.ProblemSolver.addConfigToRoadmap (   self,
  config 
)

◆ addConfigValidation()

def manipulation.problem_solver.ProblemSolver.addConfigValidation (   self,
  configValidationType 
)

◆ addEdgeToRoadmap()

def manipulation.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, if TRUE, add edges config1->config2 AND config2->config1.

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

◆ addGoalConfig()

def manipulation.problem_solver.ProblemSolver.addGoalConfig (   self,
  dofArray 
)

Add goal configuration to specified problem.

Parameters
dofArrayArray of degrees of freedom
Exceptions
Error.

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

◆ addPartialCom()

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

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

◆ addPassiveDofs()

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

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

◆ addPathOptimizer()

def manipulation.problem_solver.ProblemSolver.addPathOptimizer (   self,
  pathOptimizerType 
)

◆ applyConstraints()

def manipulation.problem_solver.ProblemSolver.applyConstraints (   self,
  q 
)

Apply constraints.

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

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

◆ balanceConstraints()

def manipulation.problem_solver.ProblemSolver.balanceConstraints (   self)

◆ clearConfigValidations()

def manipulation.problem_solver.ProblemSolver.clearConfigValidations (   self)

Clear config validations.

See also
hpp.corbaserver.problem_solver.ProblemSolver.clearConfigValidations

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

◆ clearPathOptimizers()

def manipulation.problem_solver.ProblemSolver.clearPathOptimizers (   self)

◆ clearRoadmap()

def manipulation.problem_solver.ProblemSolver.clearRoadmap (   self)

◆ concatenatePath()

def manipulation.problem_solver.ProblemSolver.concatenatePath (   self,
  pathId1,
  pathId2 
)

Concatenate two paths The function appends the second path to the first one and remove the second path.

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

◆ configAtParam()

def manipulation.problem_solver.ProblemSolver.configAtParam (   self,
  inPathId,
  atDistance 
)

Get the robot's config at param on the a path.

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

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

◆ createComBeetweenFeet()

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

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

Referenced by manipulation.problem_solver.ProblemSolver.createRelativeComConstraint().

◆ createComplementStaticStabilityConstraints()

def manipulation.problem_solver.ProblemSolver.createComplementStaticStabilityConstraints (   self,
  constraintName,
  q0 
)

Create complement of static stability constraints.

Call corba request hpp::corbaserver::wholebody_step::Problem::addComplementStaticStabilityConstraints

The ankles are defined by members leftAnkle and rightAnkle of variable robot passed at construction of this object.

Parameters
constraintNamename of the resulting constraint,
q0configuration that satisfies the constraints

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

◆ createLockedExtraDof()

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

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

◆ createLockedJoint()

def manipulation.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,

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

Referenced by manipulation.problem_solver.ProblemSolver.lockFreeFlyerJoint(), and manipulation.problem_solver.ProblemSolver.lockPlanarJoint().

◆ createOrientationConstraint()

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

Reset Constraints.

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 of joint2 is "", the corresponding joint is replaced by the global frame. constraints are stored in ProblemSolver object

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

Referenced by manipulation.problem_solver.ProblemSolver.balanceConstraints().

◆ createPlacementConstraints()

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

◆ createPositionConstraint()

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

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

Referenced by manipulation.problem_solver.ProblemSolver.createOrientationConstraint().

◆ createRelativeComConstraint()

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

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

◆ createStaticStabilityConstraints()

def manipulation.problem_solver.ProblemSolver.createStaticStabilityConstraints (   self,
  constraintName,
  q0,
  comName = "",
  type = None 
)

Create static stability constraints.

Call corba request hpp::corbaserver::wholebody_step::Problem::addStaticStabilityConstraints

The ankles are defined by members leftAnkle and rightAnkle of variable robot passed at construction of this object.

Parameters
constraintNamename of the resulting constraint,
q0configuration that satisfies the constraints,
comNamename of a partial COM,
typeType of static stability constraints (Default value: ProblemSolver.SLIDING)
See also
hpp::corbaserver::wholebody_step::Problem::StaticStabilityType

References hpp::corbaserver::benchmark::Benchmark.client, hpp::corbaserver::problem_solver::ProblemSolver.client, hpp::corbaserver::robot::Robot.client, manipulation.problem_solver.ProblemSolver.client, hpp::corbaserver::problem_solver::ProblemSolver.robot, hpp::corbaserver::benchmark::Benchmark.robot, manipulation.problem_solver.ProblemSolver.robot, hpp::corbaserver::wholebody_step::Problem.SLIDING, and manipulation.problem_solver.ProblemSolver.SLIDING.

Referenced by manipulation.problem_solver.ProblemSolver.getObstacleNames().

◆ createTransformationConstraint()

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

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

Referenced by manipulation.problem_solver.ProblemSolver.createPositionConstraint().

◆ directPath()

def manipulation.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 collission-free part from startConfig

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

◆ edge()

def manipulation.problem_solver.ProblemSolver.edge (   self,
  edgeId 
)

◆ erasePath()

def manipulation.problem_solver.ProblemSolver.erasePath (   self,
  pathId 
)

◆ executeOneStep()

def manipulation.problem_solver.ProblemSolver.executeOneStep (   self)

◆ finishSolveStepByStep()

def manipulation.problem_solver.ProblemSolver.finishSolveStepByStep (   self)

◆ generateValidConfig()

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

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

◆ getAvailable()

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

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

Referenced by manipulation.problem_solver.ProblemSolver.getConstantRightHandSide().

◆ getConstantRightHandSide()

def manipulation.problem_solver.ProblemSolver.getConstantRightHandSide (   self,
  constraintName 
)

◆ getErrorThreshold()

def manipulation.problem_solver.ProblemSolver.getErrorThreshold (   self)

◆ getGoalConfigs()

def manipulation.problem_solver.ProblemSolver.getGoalConfigs (   self)

◆ getInitialConfig()

def manipulation.problem_solver.ProblemSolver.getInitialConfig (   self)

◆ getJacobianPartialCom()

def manipulation.problem_solver.ProblemSolver.getJacobianPartialCom (   self,
  comName 
)

◆ getMaxIterations() [1/2]

def manipulation.problem_solver.ProblemSolver.getMaxIterations (   self)

◆ getMaxIterations() [2/2]

def manipulation.problem_solver.ProblemSolver.getMaxIterations (   self)

◆ getMaxIterPathPlanning()

def manipulation.problem_solver.ProblemSolver.getMaxIterPathPlanning (   self)

◆ getMaxIterProjection()

def manipulation.problem_solver.ProblemSolver.getMaxIterProjection (   self)

◆ getObstacleNames()

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

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

◆ getObstaclePosition()

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

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

◆ getParameter()

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

◆ getPartialCom()

def manipulation.problem_solver.ProblemSolver.getPartialCom (   self,
  comName 
)

◆ 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::problem_solver::ProblemSolver.client, hpp::corbaserver::robot::Robot.client, and manipulation.problem_solver.ProblemSolver.client.

◆ getWaypoints()

def manipulation.problem_solver.ProblemSolver.getWaypoints (   self,
  pathId 
)

◆ interruptPathPlanning()

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

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

◆ loadObstacleFromUrdf()

def manipulation.problem_solver.ProblemSolver.loadObstacleFromUrdf (   self,
  package,
  filename,
  prefix 
)

Load obstacle from urdf file.

Parameters
packageName of the package containing the model,
filenamename of the urdf file in the package (without suffix .urdf)
prefixprefix added to object names in case the same file is loaded several times

The ros url is built as follows: "package://${package}/urdf/${filename}.urdf"

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

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

◆ 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 hpp::corbaserver::Problem.createLockedJoint(), hpp::corbaserver::problem_solver::ProblemSolver.createLockedJoint(), and manipulation.problem_solver.ProblemSolver.createLockedJoint().

Referenced by manipulation.problem_solver.ProblemSolver.createLockedExtraDof().

◆ 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 hpp::corbaserver::Problem.createLockedJoint(), hpp::corbaserver::problem_solver::ProblemSolver.createLockedJoint(), and manipulation.problem_solver.ProblemSolver.createLockedJoint().

◆ moveObstacle()

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

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

◆ movePathToProblem()

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

◆ node()

def manipulation.problem_solver.ProblemSolver.node (   self,
  nodeId 
)

◆ nodes()

def manipulation.problem_solver.ProblemSolver.nodes (   self)

◆ nodesConnectedComponent()

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

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

◆ numberConnectedComponents()

def manipulation.problem_solver.ProblemSolver.numberConnectedComponents (   self)

◆ numberEdges()

def manipulation.problem_solver.ProblemSolver.numberEdges (   self)

◆ numberNodes()

def manipulation.problem_solver.ProblemSolver.numberNodes (   self)

◆ numberPaths()

def manipulation.problem_solver.ProblemSolver.numberPaths (   self)

◆ optimizePath()

def manipulation.problem_solver.ProblemSolver.optimizePath (   self,
  inPathId 
)

◆ pathLength()

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

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

◆ prepareSolveStepByStep()

def manipulation.problem_solver.ProblemSolver.prepareSolveStepByStep (   self)

◆ projectPath()

def manipulation.problem_solver.ProblemSolver.projectPath (   self,
  pathId 
)

◆ removeObstacleFromJoint()

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

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

Referenced by manipulation.problem_solver.ProblemSolver.loadObstacleFromUrdf().

◆ resetConstraints()

def manipulation.problem_solver.ProblemSolver.resetConstraints (   self)

Reset Constraints.

Reset all constraints, including numerical constraints and locked degrees of freedom.

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

◆ resetGoalConfigs()

def manipulation.problem_solver.ProblemSolver.resetGoalConfigs (   self)

◆ selectDistance()

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

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

◆ selectPathPlanner()

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

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

◆ selectPathProjector()

def manipulation.problem_solver.ProblemSolver.selectPathProjector (   self,
  pathProjectorType,
  tolerance 
)

Select path projector method.

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

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

◆ selectPathValidation()

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

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

◆ 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::problem_solver::ProblemSolver.client, hpp::corbaserver::robot::Robot.client, and manipulation.problem_solver.ProblemSolver.client.

◆ selectSteeringMethod()

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

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

◆ setConstantRightHandSide()

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

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

◆ setErrorThreshold()

def manipulation.problem_solver.ProblemSolver.setErrorThreshold (   self,
  threshold 
)

◆ setInitialConfig()

def manipulation.problem_solver.ProblemSolver.setInitialConfig (   self,
  dofArray 
)

Set initial configuration of specified problem.

Parameters
dofArrayArray of degrees of freedom
Exceptions
Error.

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

◆ setLockedJointConstraints()

def manipulation.problem_solver.ProblemSolver.setLockedJointConstraints (   self,
  name,
  names 
)

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

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

◆ setMaxIterations() [1/2]

def manipulation.problem_solver.ProblemSolver.setMaxIterations (   self,
  iterations 
)

◆ setMaxIterations() [2/2]

def manipulation.problem_solver.ProblemSolver.setMaxIterations (   self,
  iterations 
)

◆ setMaxIterPathPlanning()

def manipulation.problem_solver.ProblemSolver.setMaxIterPathPlanning (   self,
  iterations 
)

◆ setMaxIterProjection()

def manipulation.problem_solver.ProblemSolver.setMaxIterProjection (   self,
  iterations 
)

◆ setNumericalConstraints()

def manipulation.problem_solver.ProblemSolver.setNumericalConstraints (   self,
  name,
  names,
  priorities = None 
)

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

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

◆ setParameter()

def manipulation.problem_solver.ProblemSolver.setParameter (   self,
  name,
  value 
)

◆ setRandomSeed()

def manipulation.problem_solver.ProblemSolver.setRandomSeed (   self,
  seed 
)

◆ 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.problem_solver.ProblemSolver.client.

◆ solve()

def manipulation.problem_solver.ProblemSolver.solve (   self)

Member Data Documentation

◆ balanceConstraints_

manipulation.problem_solver.ProblemSolver.balanceConstraints_

◆ client

manipulation.problem_solver.ProblemSolver.client

Referenced by manipulation.problem_solver.ProblemSolver.addConfigToRoadmap(), manipulation.problem_solver.ProblemSolver.addConfigValidation(), manipulation.problem_solver.ProblemSolver.addEdgeToRoadmap(), manipulation.problem_solver.ProblemSolver.addGoalConfig(), manipulation.problem_solver.ProblemSolver.addPartialCom(), manipulation.problem_solver.ProblemSolver.addPassiveDofs(), manipulation.problem_solver.ProblemSolver.addPathOptimizer(), manipulation.problem_solver.ProblemSolver.applyConstraints(), manipulation.constraint_graph.ConstraintGraph.applyNodeConstraints(), manipulation.constraint_graph.ConstraintGraph.buildAndProjectPath(), manipulation.problem_solver.ProblemSolver.clearConfigValidations(), manipulation.problem_solver.ProblemSolver.clearPathOptimizers(), manipulation.problem_solver.ProblemSolver.clearRoadmap(), manipulation.robot.Robot.collisionTest(), manipulation.problem_solver.ProblemSolver.concatenatePath(), manipulation.problem_solver.ProblemSolver.configAtParam(), manipulation.problem_solver.ProblemSolver.createComBeetweenFeet(), manipulation.problem_solver.ProblemSolver.createComplementStaticStabilityConstraints(), manipulation.constraint_graph.ConstraintGraph.createGrasp(), manipulation.problem_solver.ProblemSolver.createLockedExtraDof(), manipulation.problem_solver.ProblemSolver.createLockedJoint(), manipulation.problem_solver.ProblemSolver.createOrientationConstraint(), manipulation.problem_solver.ProblemSolver.createPlacementConstraints(), manipulation.problem_solver.ProblemSolver.createPositionConstraint(), manipulation.constraint_graph.ConstraintGraph.createPreGrasp(), manipulation.problem_solver.ProblemSolver.createRelativeComConstraint(), manipulation.problem_solver.ProblemSolver.createStaticStabilityConstraints(), manipulation.problem_solver.ProblemSolver.createTransformationConstraint(), manipulation.problem_solver.ProblemSolver.directPath(), manipulation.robot.Robot.distancesToCollision(), manipulation.problem_solver.ProblemSolver.edge(), manipulation.problem_solver.ProblemSolver.erasePath(), manipulation.problem_solver.ProblemSolver.executeOneStep(), manipulation.problem_solver.ProblemSolver.finishSolveStepByStep(), manipulation.constraint_graph.ConstraintGraph.generateTargetConfig(), manipulation.problem_solver.ProblemSolver.generateValidConfig(), manipulation.robot.Robot.getAllJointNames(), manipulation.problem_solver.ProblemSolver.getAvailable(), manipulation.robot.Robot.getCenterOfMass(), manipulation.constraint_graph.ConstraintGraph.getConfigErrorForEdge(), manipulation.constraint_graph.ConstraintGraph.getConfigErrorForEdgeLeaf(), manipulation.constraint_graph.ConstraintGraph.getConfigErrorForEdgeTarget(), manipulation.constraint_graph.ConstraintGraph.getConfigErrorForNode(), manipulation.robot.Robot.getConfigSize(), manipulation.problem_solver.ProblemSolver.getConstantRightHandSide(), manipulation.robot.Robot.getCurrentConfig(), manipulation.problem_solver.ProblemSolver.getErrorThreshold(), manipulation.problem_solver.ProblemSolver.getGoalConfigs(), manipulation.robot.Robot.getGripperPositionInJoint(), manipulation.robot.Robot.getHandlePositionInJoint(), manipulation.problem_solver.ProblemSolver.getInitialConfig(), manipulation.robot.Robot.getJacobianCenterOfMass(), manipulation.problem_solver.ProblemSolver.getJacobianPartialCom(), manipulation.robot.Robot.getJointBounds(), manipulation.robot.Robot.getJointConfigSize(), manipulation.robot.Robot.getJointInnerObjects(), manipulation.robot.Robot.getJointNames(), manipulation.robot.Robot.getJointNumberDof(), manipulation.robot.Robot.getJointOuterObjects(), manipulation.robot.Robot.getJointPosition(), manipulation.robot.Robot.getLinkNames(), manipulation.robot.Robot.getLinkPosition(), manipulation.robot.Robot.getMass(), manipulation.problem_solver.ProblemSolver.getMaxIterations(), manipulation.problem_solver.ProblemSolver.getMaxIterPathPlanning(), manipulation.problem_solver.ProblemSolver.getMaxIterProjection(), manipulation.constraint_graph.ConstraintGraph.getNode(), manipulation.constraint_graph.ConstraintGraph.getNodesConnectedByEdge(), manipulation.robot.Robot.getNumberDof(), manipulation.robot.Robot.getObjectPosition(), manipulation.problem_solver.ProblemSolver.getObstacleNames(), manipulation.problem_solver.ProblemSolver.getObstaclePosition(), manipulation.problem_solver.ProblemSolver.getParameter(), manipulation.problem_solver.ProblemSolver.getPartialCom(), manipulation.robot.Robot.getRobotAABB(), manipulation.problem_solver.ProblemSolver.getSelected(), manipulation.problem_solver.ProblemSolver.getWaypoints(), manipulation.constraint_graph.ConstraintGraph.getWeight(), manipulation.robot.Robot.insertHumanoidModel(), manipulation.robot.Robot.insertObjectModel(), manipulation.robot.Robot.insertRobotModel(), manipulation.robot.Robot.insertRobotSRDFModel(), manipulation.problem_solver.ProblemSolver.interruptPathPlanning(), manipulation.robot.Robot.isConfigValid(), manipulation.constraint_graph.ConstraintGraph.isShort(), manipulation.robot.Robot.loadEnvironmentModel(), manipulation.robot.Robot.loadModel(), manipulation.robot.HumanoidRobot.loadModel(), manipulation.problem_solver.ProblemSolver.loadObstacleFromUrdf(), manipulation.problem_solver.ProblemSolver.moveObstacle(), manipulation.problem_solver.ProblemSolver.movePathToProblem(), manipulation.problem_solver.ProblemSolver.node(), manipulation.problem_solver.ProblemSolver.nodes(), manipulation.problem_solver.ProblemSolver.nodesConnectedComponent(), manipulation.problem_solver.ProblemSolver.numberConnectedComponents(), manipulation.problem_solver.ProblemSolver.numberEdges(), manipulation.problem_solver.ProblemSolver.numberNodes(), manipulation.problem_solver.ProblemSolver.numberPaths(), manipulation.problem_solver.ProblemSolver.optimizePath(), manipulation.problem_solver.ProblemSolver.pathLength(), manipulation.problem_solver.ProblemSolver.prepareSolveStepByStep(), manipulation.problem_solver.ProblemSolver.projectPath(), manipulation.problem_solver.ProblemSolver.removeObstacleFromJoint(), manipulation.robot.Robot.removeObstacleFromJoint(), manipulation.problem_solver.ProblemSolver.resetConstraints(), manipulation.problem_solver.ProblemSolver.resetGoalConfigs(), manipulation.problem_solver.ProblemSolver.selectDistance(), manipulation.problem_solver.ProblemSolver.selectPathPlanner(), manipulation.problem_solver.ProblemSolver.selectPathProjector(), manipulation.problem_solver.ProblemSolver.selectPathValidation(), manipulation.problem_solver.ProblemSolver.selectProblem(), manipulation.problem_solver.ProblemSolver.selectSteeringMethod(), manipulation.problem_solver.ProblemSolver.setConstantRightHandSide(), manipulation.robot.Robot.setCurrentConfig(), manipulation.problem_solver.ProblemSolver.setErrorThreshold(), manipulation.problem_solver.ProblemSolver.setInitialConfig(), manipulation.robot.Robot.setJointBounds(), manipulation.robot.Robot.setJointPosition(), manipulation.problem_solver.ProblemSolver.setLockedJointConstraints(), manipulation.problem_solver.ProblemSolver.setMaxIterations(), manipulation.problem_solver.ProblemSolver.setMaxIterPathPlanning(), manipulation.problem_solver.ProblemSolver.setMaxIterProjection(), manipulation.problem_solver.ProblemSolver.setNumericalConstraints(), manipulation.problem_solver.ProblemSolver.setParameter(), manipulation.constraint_graph.ConstraintGraph.setProblemConstraints(), manipulation.problem_solver.ProblemSolver.setRandomSeed(), manipulation.robot.Robot.setRootJointPosition(), manipulation.constraint_graph.ConstraintGraph.setShort(), manipulation.problem_solver.ProblemSolver.setTargetState(), manipulation.constraint_graph.ConstraintGraph.setWeight(), manipulation.robot.Robot.shootRandomConfig(), and manipulation.problem_solver.ProblemSolver.solve().

◆ FIXED_ALIGNED_COM

manipulation.problem_solver.ProblemSolver.FIXED_ALIGNED_COM = \
static

◆ FIXED_ON_THE_GROUND

manipulation.problem_solver.ProblemSolver.FIXED_ON_THE_GROUND = \
static

◆ robot

manipulation.problem_solver.ProblemSolver.robot

◆ SLIDING

manipulation.problem_solver.ProblemSolver.SLIDING = hpp.corbaserver.wholebody_step.Problem.SLIDING
static

◆ SLIDING_ALIGNED_COM

manipulation.problem_solver.ProblemSolver.SLIDING_ALIGNED_COM = \
static