Definition of a path planning problem. More...
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, 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 | 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 | |
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.
| def hpp.corbaserver.problem_solver.ProblemSolver.__init__ | ( | self, | |
| robot, | |||
hppcorbaClient = None |
|||
| ) |
| def hpp.corbaserver.problem_solver.ProblemSolver.addConfigToRoadmap | ( | self, | |
| config | |||
| ) |
Add a configuration to the roadmap.
| config | to be added to the roadmap. |
| def hpp.corbaserver.problem_solver.ProblemSolver.addConfigValidation | ( | self, | |
| configValidationType | |||
| ) |
Add path validation object.
| configValidationType | name of the config validation method |
| def hpp.corbaserver.problem_solver.ProblemSolver.addEdgeToRoadmap | ( | self, | |
| config1, | |||
| config2, | |||
| pathId, | |||
| bothEdges | |||
| ) |
Add an edge to roadmap.
If
| config1,config2 | the ends of the path, |
| pathId | the index if the path in the vector of path, |
| bothEdges | if FALSE, only add config1 to config2, otherwise, If TRUE. add edges config1->config2 AND config2->config1. |
| def hpp.corbaserver.problem_solver.ProblemSolver.addGoalConfig | ( | self, | |
| dofArray | |||
| ) |
Add goal configuration to specified problem.
| dofArray | Array of degrees of freedom |
| Error. |
| def hpp.corbaserver.problem_solver.ProblemSolver.addLockedJointConstraints | ( | self, | |
| name, | |||
| names | |||
| ) |
Add locked joint in ConfigProjector.
| name | name of the config projector created if any, |
| names | list of names of the locked joints previously created by method createLockedJoint. |
| def hpp.corbaserver.problem_solver.ProblemSolver.addNumericalConstraints | ( | self, | |
| name, | |||
| names, | |||
priorities = None |
|||
| ) |
Add numerical constraints in ConfigProjector.
| name | name of the config projector created if any, |
| names | list of names of the numerical constraints previously created by methods createTransformationConstraint, createRelativeComConstraint, ... |
| def hpp.corbaserver.problem_solver.ProblemSolver.addPartialCom | ( | self, | |
| comName, | |||
| jointNames | |||
| ) |
Add an object to compute a partial COM of the robot.
| name | of the partial com |
| jointNames | list of joint name of each tree ROOT to consider. |
| def hpp.corbaserver.problem_solver.ProblemSolver.addPassiveDofs | ( | self, | |
| name, | |||
| dofNames | |||
| ) |
Create a vector of passive dofs.
| name | name of the vector in the ProblemSolver map. |
| dofNames | list of names of DOF that may |
| def hpp.corbaserver.problem_solver.ProblemSolver.addPathOptimizer | ( | self, | |
| pathOptimizerType | |||
| ) |
Add a path optimizer.
| Name | of the path optimizer type, either "RandomShortcut" or any type added by core::ProblemSolver::addPathOptimizerType |
| def hpp.corbaserver.problem_solver.ProblemSolver.appendDirectPath | ( | self, | |
| pathId, | |||
| config, | |||
| validate | |||
| ) |
Append a path to an existing path.
| pathId | Id of the path in this problem, |
| config | end configuration of the new path. |
| Error | if 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. |
| def hpp.corbaserver.problem_solver.ProblemSolver.applyConstraints | ( | self, | |
| q | |||
| ) |
Apply constraints.
| q | initial configuration |
| Error | if projection failed. |
| def hpp.corbaserver.problem_solver.ProblemSolver.clearPathOptimizers | ( | self | ) |
Clear sequence of path optimizers.
| def hpp.corbaserver.problem_solver.ProblemSolver.clearRoadmap | ( | self | ) |
Clear the roadmap.
| def hpp.corbaserver.problem_solver.ProblemSolver.computeValueAndJacobian | ( | self, | |
| q | |||
| ) |
Compute value and Jacobian of numerical constraints.
| q | input configuration |
Columns of the Jacobian corresponding to locked joints are omitted, columns corresponding to passive dofs are set to 0.
| def hpp.corbaserver.problem_solver.ProblemSolver.concatenatePath | ( | self, | |
| startId, | |||
| endId | |||
| ) |
Concatenate path endId at the end of startId.
| def hpp.corbaserver.problem_solver.ProblemSolver.configAtParam | ( | self, | |
| inPathId, | |||
| param | |||
| ) |
Get the robot config at param on a path.
| inPathId | rank of the path in the problem |
| param | : the user parameter choice |
| def hpp.corbaserver.problem_solver.ProblemSolver.createComBeetweenFeet | ( | self, | |
| constraintName, | |||
| comName, | |||
| jointLName, | |||
| jointRName, | |||
| pointL, | |||
| pointR, | |||
| jointRefName, | |||
| mask | |||
| ) |
Create ComBeetweenFeet constraint between two joints.
| constraintName | name of the constraint created, |
| comName | name of CenterOfMassComputation |
| jointLName | name of first joint |
| jointRName | name of second joint |
| pointL | point in local frame of jointL. |
| pointR | point in local frame of jointR. |
| jointRefName | name of second joint |
| mask | Select axis to be constrained. If jointRef is "", the robot root joint is used. Constraints are stored in ProblemSolver object |
Referenced by hpp.corbaserver.problem_solver.ProblemSolver.createRelativeComConstraint().
| def hpp.corbaserver.problem_solver.ProblemSolver.createDistanceBetweenJointAndObjects | ( | self, | |
| constraintName, | |||
| joint1Name, | |||
| objects, | |||
| distance | |||
| ) |
Create distance constraint between robot and environment objects.
| constraintName | name of the constraint created, |
| joint1Name | name of first joint, |
| objects | names of environment objects, |
| distance | desired distance between joint bodies. Constraints are stored in ProblemSolver object |
Referenced by hpp.corbaserver.problem_solver.ProblemSolver.createDistanceBetweenJointConstraint().
| def hpp.corbaserver.problem_solver.ProblemSolver.createDistanceBetweenJointConstraint | ( | self, | |
| constraintName, | |||
| joint1Name, | |||
| joint2Name, | |||
| distance | |||
| ) |
Create distance constraint between robot objects.
| constraintName | name of the constraint created, |
| joint1Name | name of first joint, |
| joint2Name | name of second joint, |
| distance | desired distance between joint bodies. Constraints are stored in ProblemSolver object |
References hpp.corbaserver.problem_solver.ProblemSolver.createDistanceBetweenJointAndObjects().
Referenced by hpp.corbaserver.problem_solver.ProblemSolver.createPositionConstraint().
| def hpp.corbaserver.problem_solver.ProblemSolver.createLockedExtraDof | ( | self, | |
| lockedDofName, | |||
| index, | |||
| value | |||
| ) |
Create a locked extradof hpp::manipulation::ProblemSolver map.
| lockedDofName | key of the constraint in the Problem Solver map |
| index | index of the extra dof (0 means the first extra dof) |
| value | value of the extra dof configuration. The size of this vector defines the size of the constraints. |
| def hpp.corbaserver.problem_solver.ProblemSolver.createLockedJoint | ( | self, | |
| lockedDofName, | |||
| jointName, | |||
| value | |||
| ) |
Create a LockedJoint constraint with given value.
| lockedJointName | key of the constraint in the ProblemSolver map, |
| jointName | name of the joint, |
| value | value of the joint configuration, |
| def hpp.corbaserver.problem_solver.ProblemSolver.createOrientationConstraint | ( | self, | |
| constraintName, | |||
| joint1Name, | |||
| joint2Name, | |||
| p, | |||
| mask | |||
| ) |
Create orientation constraint between two joints.
| constraintName | name of the constraint created, |
| joint1Name | name of first joint |
| joint2Name | name of second joint |
| p | quaternion representing the desired orientation of joint2 in the frame of joint1. |
| mask | Select 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 |
References hpp.corbaserver.problem_solver.ProblemSolver.createTransformationConstraint().
Referenced by hpp.corbaserver.problem_solver.ProblemSolver.getObstacleLinkNames().
| def hpp.corbaserver.problem_solver.ProblemSolver.createPositionConstraint | ( | self, | |
| constraintName, | |||
| joint1Name, | |||
| joint2Name, | |||
| point1, | |||
| point2, | |||
| mask | |||
| ) |
Create position constraint between two joints.
| constraintName | name of the constraint created, |
| joint1Name | name of first joint |
| joint2Name | name of second joint |
| point1 | point in local frame of joint1, |
| point2 | point in local frame of joint2. |
| mask | Select 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.problem_solver.ProblemSolver.createDistanceBetweenJointConstraint().
Referenced by hpp.corbaserver.problem_solver.ProblemSolver.getPartialCom().
| def hpp.corbaserver.problem_solver.ProblemSolver.createRelativeComConstraint | ( | self, | |
| constraintName, | |||
| comName, | |||
| jointLName, | |||
| point, | |||
| mask | |||
| ) |
Create RelativeCom constraint between two joints.
| constraintName | name of the constraint created, |
| comName | name of CenterOfMassComputation |
| jointName | name of joint |
| point | point in local frame of joint. |
| mask | Select axis to be constrained. If jointName is "", the robot root joint is used. Constraints are stored in ProblemSolver object |
References hpp.corbaserver.problem_solver.ProblemSolver.createComBeetweenFeet().
| def hpp.corbaserver.problem_solver.ProblemSolver.createTransformationConstraint | ( | self, | |
| constraintName, | |||
| joint1Name, | |||
| joint2Name, | |||
| ref, | |||
| mask | |||
| ) |
Create transformation constraint between two joints.
| constraintName | name of the constraint created, |
| joint1Name | name of first joint |
| joint2Name | name of second joint |
| ref | desired transformation of joint2 in the frame of joint1. |
| mask | Select 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 |
Referenced by hpp.corbaserver.problem_solver.ProblemSolver.createOrientationConstraint().
| def hpp.corbaserver.problem_solver.ProblemSolver.cutObstacle | ( | self, | |
| objectName, | |||
| aabb | |||
| ) |
Cut the obstacle with the given AABB.
| aabb | a vector of 6 floats. The 3 first represent one corner and the 3 last represent the opposite corner. |
| def hpp.corbaserver.problem_solver.ProblemSolver.derivativeAtParam | ( | self, | |
| inPathId, | |||
| order, | |||
| param | |||
| ) |
Get the robot velocity at param on a path.
| inPathId | rank of the path in the problem |
| orderId | order of the derivative |
| param | : the user parameter choice |
| def hpp.corbaserver.problem_solver.ProblemSolver.directPath | ( | self, | |
| startConfig, | |||
| endConfig, | |||
| validate | |||
| ) |
Make direct connection between two configurations.
| startConfig,endConfig | the configurations to link. |
| validate | whether path should be validated. If true, path validation is called and only valid part of path is inserted in the path vector. |
| def hpp.corbaserver.problem_solver.ProblemSolver.edge | ( | self, | |
| edgeId | |||
| ) |
Edge at given rank.
| def hpp.corbaserver.problem_solver.ProblemSolver.erasePath | ( | self, | |
| pathId | |||
| ) |
Erase path pathId from stored.
| def hpp.corbaserver.problem_solver.ProblemSolver.executeOneStep | ( | self | ) |
| def hpp.corbaserver.problem_solver.ProblemSolver.extractPath | ( | self, | |
| pathId, | |||
| start, | |||
| end | |||
| ) |
extract path pathId from param start to end
| def hpp.corbaserver.problem_solver.ProblemSolver.filterCollisionPairs | ( | self | ) |
Build matrix of relative motions between joints.
See hpp::core::Problem::filterCollisionPairs.
| def hpp.corbaserver.problem_solver.ProblemSolver.finishSolveStepByStep | ( | self | ) |
| def hpp.corbaserver.problem_solver.ProblemSolver.generateValidConfig | ( | self, | |
| maxIter | |||
| ) |
Generate a configuration satisfying the constraints.
| maxIter | maximum number of tries, |
| Error | if projection failed. |
| def hpp.corbaserver.problem_solver.ProblemSolver.getAvailable | ( | self, | |
| type | |||
| ) |
Return a list of available elements of type type.
| type | enter "type" to know what types I know of. This is case insensitive. |
| def hpp.corbaserver.problem_solver.ProblemSolver.getConstantRightHandSide | ( | self, | |
| constraintName | |||
| ) |
Get whether right hand side of a numerical constraint is constant.
| constraintName | Name of the numerical constraint, |
| def hpp.corbaserver.problem_solver.ProblemSolver.getErrorThreshold | ( | self | ) |
error threshold in numerical constraint resolution
| def hpp.corbaserver.problem_solver.ProblemSolver.getGoalConfigs | ( | self | ) |
Get goal configurations of specified problem.
| def hpp.corbaserver.problem_solver.ProblemSolver.getInitialConfig | ( | self | ) |
Get initial configuration of specified problem.
| def hpp.corbaserver.problem_solver.ProblemSolver.getMaxIterPathPlanning | ( | self | ) |
Get the maximal number of iterations in projection.
| def hpp.corbaserver.problem_solver.ProblemSolver.getMaxIterProjection | ( | self | ) |
Get the maximal number of iterations in projection.
| def hpp.corbaserver.problem_solver.ProblemSolver.getMaxNumThreads | ( | self | ) |
Get the maximum number of concurrent access to the device (in thread safe areas).
| def hpp.corbaserver.problem_solver.ProblemSolver.getNearestConfig | ( | self, | |
| randomConfig, | |||
connectedComponentId = -1 |
|||
| ) |
Return nearest neighbour of given input configuration.
| connectedComponentId | is 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). |
| distance | returns the one-dimensional distance between |
| config | and computed nearest node (configuration). |
| def hpp.corbaserver.problem_solver.ProblemSolver.getObstacleLinkNames | ( | self | ) |
Get list of obstacles.
| collision | whether to return obstacle for collision, |
| distance | whether to return obstacles for distance computation |
References hpp.corbaserver.problem_solver.ProblemSolver.createOrientationConstraint().
| def hpp.corbaserver.problem_solver.ProblemSolver.getObstacleLinkPosition | ( | self, | |
| objectName | |||
| ) |
| def hpp.corbaserver.problem_solver.ProblemSolver.getObstacleNames | ( | self, | |
| collision, | |||
| distance | |||
| ) |
Get list of obstacles.
| collision | whether to return obstacle for collision, |
| distance | whether to return obstacles for distance computation |
| def hpp.corbaserver.problem_solver.ProblemSolver.getObstaclePosition | ( | self, | |
| objectName | |||
| ) |
Get the position of an obstacle.
| objectName | name of the polyhedron. |
| cfg | Position of the obstacle. |
| Error. |
| 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.
| def hpp.corbaserver.problem_solver.ProblemSolver.getParameterDoc | ( | self, | |
| name | |||
| ) |
Get parameter documentation raise an exception when the parameter is not found.
| def hpp.corbaserver.problem_solver.ProblemSolver.getPartialCom | ( | self, | |
| comName | |||
| ) |
| def hpp.corbaserver.problem_solver.ProblemSolver.getSelected | ( | self, | |
| type | |||
| ) |
Return a list of selected elements of type type.
| type | enter "type" to know what types I know of. This is case insensitive. |
| def hpp.corbaserver.problem_solver.ProblemSolver.getTimeOutPathPlanning | ( | self | ) |
Get time out in path planning (in seconds)
| def hpp.corbaserver.problem_solver.ProblemSolver.getWaypoints | ( | self, | |
| pathId | |||
| ) |
Get way points of a path.
| pathId | rank of the path in the problem |
| def hpp.corbaserver.problem_solver.ProblemSolver.interruptPathPlanning | ( | self | ) |
Interrupt path planning activity.
| def hpp.corbaserver.problem_solver.ProblemSolver.loadObstacleFromUrdf | ( | self, | |
| package, | |||
| filename, | |||
| prefix | |||
| ) |
Load obstacle from urdf file.
| package | Name of the package containing the model, |
| filename | name of the urdf file in the package (without suffix .urdf) |
| prefix | prefix 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.problem_solver.ProblemSolver.removeObstacleFromJoint().
| def hpp.corbaserver.problem_solver.ProblemSolver.loadPlugin | ( | self, | |
| pluginName | |||
| ) |
Load a plugin into the current ProblemSolver.
| pluginName | either an absolute filename or a filename relative to <a_path_in_LD_LIBRARY_PATH>/hppPlugins. |
| def hpp.corbaserver.problem_solver.ProblemSolver.moveObstacle | ( | self, | |
| objectName, | |||
| cfg | |||
| ) |
Move an obstacle to a given configuration.
| objectName | name of the polyhedron. |
| cfg | the configuration of the obstacle. |
| Error. |
| def hpp.corbaserver.problem_solver.ProblemSolver.movePathToProblem | ( | self, | |
| pathId, | |||
| problemName, | |||
| jointNames | |||
| ) |
| def hpp.corbaserver.problem_solver.ProblemSolver.node | ( | self, | |
| nodeId | |||
| ) |
| def hpp.corbaserver.problem_solver.ProblemSolver.nodes | ( | self | ) |
Get nodes of the roadmap.
| def hpp.corbaserver.problem_solver.ProblemSolver.nodesConnectedComponent | ( | self, | |
| ccId | |||
| ) |
Nodes of a connected component.
| connectedComponentId | index of connected component in roadmap |
| def hpp.corbaserver.problem_solver.ProblemSolver.numberConnectedComponents | ( | self | ) |
Number of connected components.
| def hpp.corbaserver.problem_solver.ProblemSolver.numberEdges | ( | self | ) |
Number of edges.
| def hpp.corbaserver.problem_solver.ProblemSolver.numberNodes | ( | self | ) |
| def hpp.corbaserver.problem_solver.ProblemSolver.numberPaths | ( | self | ) |
Get Number of paths.
| def hpp.corbaserver.problem_solver.ProblemSolver.optimize | ( | self, | |
| q | |||
| ) |
Find a local minimum of the least priority constraints.
while respecting the other priorities.
| input | input configuration, |
| def hpp.corbaserver.problem_solver.ProblemSolver.optimizePath | ( | self, | |
| inPathId | |||
| ) |
Optimize a given path.
| inPathId | Id of the path in this problem. |
| Error. |
| def hpp.corbaserver.problem_solver.ProblemSolver.pathLength | ( | self, | |
| inPathId | |||
| ) |
Get length of path.
| inPathId | rank of the path in the problem |
| def hpp.corbaserver.problem_solver.ProblemSolver.prepareSolveStepByStep | ( | self | ) |
| def hpp.corbaserver.problem_solver.ProblemSolver.projectPath | ( | self, | |
| pathId | |||
| ) |
Project path using the path projector.
| def hpp.corbaserver.problem_solver.ProblemSolver.readRoadmap | ( | self, | |
| filename | |||
| ) |
Read a roadmap from a file.
| filename | name of the file from which the roadmap is read. |
| def hpp.corbaserver.problem_solver.ProblemSolver.removeObstacleFromJoint | ( | self, | |
| objectName, | |||
| jointName, | |||
| collision, | |||
| distance | |||
| ) |
Remove an obstacle from outer objects of a joint body.
| objectName | name of the object to remove, |
| jointName | name of the joint owning the body, |
| collision | whether collision with object should be computed, |
| distance | whether distance to object should be computed. |
| Error. |
Referenced by hpp.corbaserver.problem_solver.ProblemSolver.loadObstacleFromUrdf().
| 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.
| def hpp.corbaserver.problem_solver.ProblemSolver.resetConstraints | ( | self | ) |
Reset Constraints.
Reset all constraints, including numerical constraints and locked joints
| def hpp.corbaserver.problem_solver.ProblemSolver.resetGoalConfigs | ( | self | ) |
Reset goal configurations.
| def hpp.corbaserver.problem_solver.ProblemSolver.saveRoadmap | ( | self, | |
| filename | |||
| ) |
Save the current roadmap in a file.
| filename | name of the file where the roadmap is saved |
| def hpp.corbaserver.problem_solver.ProblemSolver.selectConfigurationShooter | ( | self, | |
| configurationShooterType | |||
| ) |
Select configuration shooter type.
| Name | of the configuration shooter type |
Referenced by hpp.corbaserver.problem_solver.ProblemSolver.selectConfigurationShooter().
| def hpp.corbaserver.problem_solver.ProblemSolver.selectConfigurationShooter | ( | self, | |
| type | |||
| ) |
Select configuration shooter type.
| Name | of the configuration shooter type |
References hpp.corbaserver.problem_solver.ProblemSolver.selectConfigurationShooter().
| def hpp.corbaserver.problem_solver.ProblemSolver.selectDistance | ( | self, | |
| distanceType | |||
| ) |
Select distance type.
| Name | of the distance type, either "WeighedDistance" or any type added by method core::ProblemSolver::addDistanceType |
| def hpp.corbaserver.problem_solver.ProblemSolver.selectPathPlanner | ( | self, | |
| pathPlannerType | |||
| ) |
Select path planner type.
| Name | of the path planner type, either "DiffusingPlanner", "VisibilityPrmPlanner", or any type added by method core::ProblemSolver::addPathPlannerType |
| def hpp.corbaserver.problem_solver.ProblemSolver.selectPathProjector | ( | self, | |
| pathProjectorType, | |||
| tolerance | |||
| ) |
Select path projector method.
| Name | of the path projector method, either "Discretized" "Progressive", "Dichotomy", or any type added by core::ProblemSolver::addPathProjectorType, |
| tolerance | maximal acceptable penetration. |
| def hpp.corbaserver.problem_solver.ProblemSolver.selectPathValidation | ( | self, | |
| pathValidationType, | |||
| tolerance | |||
| ) |
Select path validation method.
| Name | of the path validation method, either "Discretized" "Progressive", "Dichotomy", or any type added by core::ProblemSolver::addPathValidationType, |
| tolerance | maximal acceptable penetration. |
| def hpp.corbaserver.problem_solver.ProblemSolver.selectProblem | ( | self, | |
| name | |||
| ) |
| def hpp.corbaserver.problem_solver.ProblemSolver.selectSteeringMethod | ( | self, | |
| steeringMethodType | |||
| ) |
Select steering method type.
| Name | of the steering method type, either "SteeringMethodStraight" or any type added by method core::ProblemSolver::addSteeringMethodType |
| def hpp.corbaserver.problem_solver.ProblemSolver.setConstantRightHandSide | ( | self, | |
| constraintName, | |||
| constant | |||
| ) |
(Dis-)Allow to modify right hand side of a numerical constraint
| constraintName | Name of the numerical constraint, |
| constant | whether right hand side is constant |
Constraints should have been added in the ProblemSolver local map, but not inserted in the config projector.
| def hpp.corbaserver.problem_solver.ProblemSolver.setDefaultLineSearchType | ( | self, | |
| type | |||
| ) |
set the default line search type used in the projection.
| See | hpp::core::ConfigProjector::LineSearchType for possible values. |
| def hpp.corbaserver.problem_solver.ProblemSolver.setErrorThreshold | ( | self, | |
| threshold | |||
| ) |
error threshold in numerical constraint resolution
| def hpp.corbaserver.problem_solver.ProblemSolver.setInitialConfig | ( | self, | |
| dofArray | |||
| ) |
Set initial configuration of specified problem.
| dofArray | Array of degrees of freedom |
| Error. |
| def hpp.corbaserver.problem_solver.ProblemSolver.setMaxIterPathPlanning | ( | self, | |
| iterations | |||
| ) |
Set the maximal number of iterations in projection.
| def hpp.corbaserver.problem_solver.ProblemSolver.setMaxIterProjection | ( | self, | |
| iterations | |||
| ) |
Set the maximal number of iterations in projection.
| 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.
| def hpp.corbaserver.problem_solver.ProblemSolver.setParameter | ( | self, | |
| name, | |||
| value | |||
| ) |
| def hpp.corbaserver.problem_solver.ProblemSolver.setRandomSeed | ( | self, | |
| seed | |||
| ) |
Set random seed of random number generator.
| def hpp.corbaserver.problem_solver.ProblemSolver.setRightHandSide | ( | self, | |
| rhs | |||
| ) |
Set right hand side of constraints in config projector.
| rhs | right hand side of constraints. Contains only right hand side of non-constant constraints |
| def hpp.corbaserver.problem_solver.ProblemSolver.setRightHandSideByName | ( | self, | |
| constraintName, | |||
| rhs | |||
| ) |
Set right hand side of given constraint in config projector.
| constraintName | name of the numerical constraint or locked joint |
| rhs | right hand side of constraint. raises an exception if constraint has constant right hand side. |
| def hpp.corbaserver.problem_solver.ProblemSolver.setRightHandSideFromConfig | ( | self, | |
| config | |||
| ) |
Set right hand side of constraints in config projector.
| config | a robot configuration use to compute the right hand side of constraints. Contains only right hand side of non-constant constraints |
| def hpp.corbaserver.problem_solver.ProblemSolver.setRightHandSideFromConfigByName | ( | self, | |
| constraintName, | |||
| config | |||
| ) |
Set right hand side of given constraint in config projector.
| constraintName | name of the numerical constraint or locked joint |
| config | a robot configuration use to compute the right hand side. raises an exception if constraint has constant right hand side. |
| def hpp.corbaserver.problem_solver.ProblemSolver.setTimeOutPathPlanning | ( | self, | |
| timeOut | |||
| ) |
Set time out in path planning (in seconds)
| def hpp.corbaserver.problem_solver.ProblemSolver.solve | ( | self | ) |
Solve the problem of corresponding ChppPlanner object.
| hpp.corbaserver.problem_solver.ProblemSolver.client |
| hpp.corbaserver.problem_solver.ProblemSolver.hppcorba |
| hpp.corbaserver.problem_solver.ProblemSolver.robot |