|
hpp-corbaserver 6.0.0
Corba server for Humanoid Path Planner applications
|
To define and solve a path planning problem. More...
import </root/robotpkg/path/py-hpp-corbaserver/work/hpp-corbaserver-6.0.0/idl/hpp/corbaserver/problem.idl;
Public Member Functions | |
| void | setRandomSeed (in long seed) raises (Error) |
| Set random seed of random number generator. | |
| void | setMaxNumThreads (in unsigned short n) raises (Error) |
| unsigned short | getMaxNumThreads () raises (Error) |
| Names_t | getAvailable (in string type) raises (Error) |
| Names_t | getSelected (in string type) raises (Error) |
| void | setParameter (in string name, in any value) raises (Error) |
| any | getParameter (in string name) raises (Error) |
| string | getParameterDoc (in string name) raises (Error) |
| boolean | selectProblem (in string name) raises (Error) |
| void | resetProblem () raises (Error) |
| Reset the current problem. | |
| boolean | loadPlugin (in string pluginName) raises (Error) |
| void | movePathToProblem (in unsigned long pathId, in string problemName, in Names_t jointNames) raises (Error) |
| core_idl::Distance | getDistance () raises (Error) |
| void | setDistance (in core_idl::Distance distance) raises (Error) |
| core_idl::Path | getPath (in unsigned long pathId) raises (Error) |
| unsigned long | addPath (in core_idl::PathVector _path) raises (Error) |
| void | savePath (in core_idl::Path _path, in string filename) raises (Error) |
| core_idl::Path | loadPath (in string filename) raises (Error) |
| core_idl::SteeringMethod | getSteeringMethod () raises (Error) |
| core_idl::PathValidation | getPathValidation () raises (Error) |
| core_idl::PathPlanner | getPathPlanner () raises (Error) |
| core_idl::Problem | getProblem () raises (Error) |
| constraints_idl::Implicit | getConstraint (in string constraintName) raises (Error) |
| void | setRobot (in pinocchio_idl::Device robot) raises (Error) |
| pinocchio_idl::CollisionObject | getObstacle (in string name) raises (Error) |
Initial and goal configurations | |
| void | setInitialConfig (in floatSeq dofArray) raises (Error) |
| floatSeq | getInitialConfig () raises (Error) |
| void | addGoalConfig (in floatSeq dofArray) raises (Error) |
| Add goal configuration to specified problem. | |
| floatSeqSeq | getGoalConfigs () raises (Error) |
| void | resetGoalConfigs () raises (Error) |
| Reset goal configurations. | |
| void | setGoalConstraints (in Names_t constraints) raises (Error) |
| Set goal as a task. | |
| void | resetGoalConstraints () raises (Error) |
| Clear goal constraints. | |
Constraints | |
| boolean | applyConstraints (in floatSeq input, out floatSeq output, out double residualError) raises (Error) |
| boolean | optimize (in floatSeq input, out floatSeq output, out floatSeq residualError) raises (Error) |
| void | computeValueAndJacobian (in floatSeq config, out floatSeq value, out floatSeqSeq jacobian) raises (Error) |
| boolean | generateValidConfig (in unsigned long maxIter, out floatSeq output, out double residualError) raises (Error) |
| void | createOrientationConstraint (in string constraintName, in string joint1Name, in string joint2Name, in Quaternion_ p, in boolSeq mask) raises (Error) |
| void | createTransformationConstraint (in string constraintName, in string joint1Name, in string joint2Name, in Transform_ ref, in boolSeq mask) raises (Error) |
| void | createTransformationR3xSO3Constraint (in string constraintName, in string joint1Name, in string joint2Name, in Transform_ frame1, in Transform_ frame2, in boolSeq mask) raises (Error) |
| void | createTransformationConstraint2 (in string constraintName, in string joint1Name, in string joint2Name, in Transform_ frame1, in Transform_ frame2, in boolSeq mask) raises (Error) |
| void | createLockedJoint (in string lockedJointName, in string jointName, in floatSeq value) raises (Error) |
| void | createLockedJointWithComp (in string lockedJointName, in string jointName, in floatSeq value, in ComparisonTypes_t comp) raises (Error) |
| void | createLockedExtraDof (in string lockedDofName, in unsigned long index, in floatSeq value) raises (Error) |
| void | createManipulability (in string name, in string function) raises (Error) |
| void | createComBeetweenFeet (in string constraintName, in string comName, in string jointLName, in string jointRName, in floatSeq pointL, in floatSeq pointR, in string jointRefName, in floatSeq pointRef, in boolSeq mask) raises (Error) |
| void | createRelativeComConstraint (in string constraintName, in string comName, in string jointLName, in floatSeq point, in boolSeq mask) raises (Error) |
| void | createConvexShapeContactConstraint (in string constraintName, in Names_t floorJoints, in Names_t objectJoints, in floatSeqSeq pts, in intSeqSeq objectTriangles, in intSeqSeq floorTriangles) raises (Error) |
| void | createPositionConstraint (in string constraintName, in string joint1Name, in string joint2Name, in floatSeq point1, in floatSeq point2, in boolSeq mask) raises (Error) |
| void | createConfigurationConstraint (in string constraintName, in floatSeq goal, in floatSeq weights) raises (Error) |
| void | createDistanceBetweenJointConstraint (in string constraintName, in string joint1Name, in string joint2Name, in double distance) raises (Error) |
| void | createDistanceBetweenJointAndObjects (in string constraintName, in string joint1Name, in Names_t objects, in double distance) raises (Error) |
| void | createIdentityConstraint (in string constraintName, in Names_t inJoints, in Names_t outJoints) raises (Error) |
| void | resetConstraints () raises (Error) |
| Reset constraints. | |
| void | resetConstraintMap () raises (Error) |
| void | addPassiveDofs (in string constraintName, in Names_t jointNames) raises (Error) |
| void | getConstraintDimensions (in string constraintName, out unsigned long inputSize, out unsigned long inputDerivativeSize, out unsigned long outputSize, out unsigned long outputDerivativeSize) raises (Error) |
| Get constraint dimensions. | |
| void | setConstantRightHandSide (in string constraintName, in boolean constant) raises (Error) |
| boolean | getConstantRightHandSide (in string constraintName) raises (Error) |
| floatSeq | getRightHandSide () raises (Error) |
| Get right hand side of constraints in config projector. | |
| void | setRightHandSide (in floatSeq rhs) raises (Error) |
| void | setRightHandSideFromConfig (in floatSeq config) raises (Error) |
| void | setRightHandSideByName (in string constraintName, in floatSeq rhs) raises (Error) |
| void | setRightHandSideFromConfigByName (in string constraintName, in floatSeq config) raises (Error) |
| void | addNumericalConstraints (in string configProjName, in Names_t constraintNames, in intSeq priorities) raises (Error) |
| void | setNumericalConstraintsLastPriorityOptional (in boolean optional) raises (Error) |
| void | addLockedJointConstraints (in string configProjName, in Names_t lockedJointNames) raises (Error) |
| string | displayConstraints () raises (Error) |
| Display the constraint in the ConfigProjector. | |
| double | getErrorThreshold () raises (Error) |
| Get error threshold in numerical constraint resolution. | |
| void | setErrorThreshold (in double threshold) raises (Error) |
| Set error threshold in numerical constraint resolution. | |
| void | setDefaultLineSearchType (in string type) raises (Error) |
| unsigned long | getMaxIterProjection () raises (Error) |
| Set maximal number of iterations in numerical constraint resolution. | |
| void | setMaxIterProjection (in unsigned long iterations) raises (Error) |
| Set maximal number of iterations in numerical constraint resolution. | |
| unsigned long | getMaxIterPathPlanning () raises (Error) |
| Get maximal number of iterations in path planning. | |
| void | setMaxIterPathPlanning (in unsigned long iterations) raises (Error) |
| Set maximal number of iterations in path planning. | |
Symbolic calculus | |
| void | scCreateScalarMultiply (in string outName, in double scalar, in string inName) raises (Error) |
| See hpp::constraints::ScalarMultiply. | |
| double | getTimeOutPathPlanning () raises (Error) |
| Get time out in path planning (in seconds) | |
| void | setTimeOutPathPlanning (in double timeOut) raises (Error) |
| Set time out in path planning (in seconds) | |
Collision checking | |
| void | filterCollisionPairs () raises (Error) |
Solve problem and get paths | |
| void | selectPathPlanner (in string pathPlannerType) raises (Error) |
| void | selectConfigurationShooter (in string configurationShooterType) raises (Error) |
| void | selectDistance (in string distanceType) raises (Error) |
| void | selectSteeringMethod (in string steeringMethodType) raises (Error) |
| void | addPathOptimizer (in string pathOptimizerType) raises (Error) |
| void | clearPathOptimizers () raises (Error) |
| Clear the vector of path optimizers. | |
| void | addConfigValidation (in string configValidationType) raises (Error) |
| void | clearConfigValidations () raises (Error) |
| Clear the vector of config validations. | |
| void | selectPathValidation (in string pathValidationType, in double tolerance) raises (Error) |
| void | selectPathProjector (in string pathProjectorType, in double tolerance) raises (Error) |
| boolean | prepareSolveStepByStep () raises (Error) |
| boolean | executeOneStep () raises (Error) |
| void | finishSolveStepByStep () raises (Error) |
| intSeq | solve () raises (Error) |
| boolean | directPath (in floatSeq startConfig, in floatSeq endConfig, in boolean validate, out unsigned long pathId, out string report) raises (Error) |
| boolean | reversePath (in unsigned long pathId, out unsigned long reversedPathId) raises (Error) |
| void | addConfigToRoadmap (in floatSeq config) raises (Error) |
| void | addEdgeToRoadmap (in floatSeq config1, in floatSeq config2, in unsigned long pathId, in boolean bothEdges) raises (Error) |
| void | appendDirectPath (in unsigned long pathId, in floatSeq config, in boolean validate) raises (Error) |
| void | concatenatePath (in unsigned long startId, in unsigned long endId) raises (Error) |
| void | extractPath (in unsigned long pathId, in double start, in double end) raises (Error) |
| void | erasePath (in unsigned long pathId) raises (Error) |
| boolean | projectPath (in unsigned long patId) raises (Error) |
| long | numberPaths () raises (Error) |
| Get Number of paths. | |
| intSeq | optimizePath (in unsigned long inPathId) raises (Error) |
| double | pathLength (in unsigned long inPathId) raises (Error) |
| floatSeq | configAtParam (in unsigned long inPathId, in double atDistance) raises (Error) |
| floatSeq | derivativeAtParam (in unsigned long inPathId, in unsigned long orderId, in double atDistance) raises (Error) |
| floatSeqSeq | getWaypoints (in unsigned long pathId, out floatSeq times) raises (Error) |
Interruption of a path planning request | |
| void | interruptPathPlanning () raises (Error) |
| Interrupt path planning activity. | |
exploring the roadmap | |
| floatSeqSeq | nodes () raises (Error) |
| Nodes of the roadmap. | |
| long | numberNodes () raises (Error) |
| floatSeq | node (in unsigned long nodeId) raises (Error) |
| long | connectedComponentOfEdge (in unsigned long edgeId) raises (Error) |
| return the connected component index of the edge | |
| long | connectedComponentOfNode (in unsigned long nodeId) raises (Error) |
| return the connected component index of the node | |
| long | numberEdges () raises (Error) |
| Number of edges. | |
| void | edge (in unsigned long edgeId, out floatSeq q1, out floatSeq q2) raises (Error) |
| Edge at given rank. | |
| long | numberConnectedComponents () |
| Number of connected components. | |
| floatSeqSeq | nodesConnectedComponent (in unsigned long connectedComponentId) raises (Error) |
| floatSeq | getNearestConfig (in floatSeq config, in long connectedComponentId, out double distance) raises (Error) |
| void | clearRoadmap () raises (Error) |
| Clear the roadmap. | |
| void | resetRoadmap () raises (Error) |
| void | saveRoadmap (in string filename) raises (Error) |
| void | loadRoadmap (in string filename) raises (Error) |
Factories | |
| core_idl::Problem | createProblem (in pinocchio_idl::Device robot) raises (Error) |
| core_idl::Roadmap | createRoadmap (in core_idl::Distance distance, in pinocchio_idl::Device robot) raises (Error) |
| core_idl::Roadmap | readRoadmap (in string filename, in pinocchio_idl::Device robot) raises (Error) |
| void | writeRoadmap (in string filename, in core_idl::Roadmap roadmap, in pinocchio_idl::Device robot) raises (Error) |
| core_idl::PathPlanner | createPathPlanner (in string type, in core_idl::Problem _problem, in core_idl::Roadmap roadmap) raises (Error) |
| core_idl::PathOptimizer | createPathOptimizer (in string type, in core_idl::Problem _problem) raises (Error) |
| core_idl::ConfigValidation | createConfigValidation (in string type, in pinocchio_idl::Device robot) raises (Error) |
| core_idl::PathValidation | createPathValidation (in string type, in pinocchio_idl::Device robot, in value_type parameter) raises (Error) |
| core_idl::PathProjector | createPathProjector (in string type, in core_idl::Problem robot, in value_type parameter) raises (Error) |
| core_idl::ConfigurationShooter | createConfigurationShooter (in string type, in core_idl::Problem _problem) raises (Error) |
| core_idl::Distance | createDistance (in string type, in core_idl::Problem _problem) raises (Error) |
| core_idl::SteeringMethod | createSteeringMethod (in string type, in core_idl::Problem _problem) raises (Error) |
| core_idl::Constraint | createConstraintSet (in pinocchio_idl::Device robot, in string name) raises (Error) |
| core_idl::Constraint | createConfigProjector (in pinocchio_idl::Device robot, in string name, in double threshold, in unsigned long iterations) raises (Error) |
To define and solve a path planning problem.
add a configuration to a roadmap
| config | Configuration to add |
A node is created if necessary.
| void hpp::corbaserver::Problem::addConfigValidation | ( | in string | configValidationType | ) | |
| raises | ( | Error | |||
| ) | |||||
Add a config validation
| Name | of the config validation type, either "CollisionValidation" or "JointBoundValidation" or any type added by core::ProblemSolver::addConfigValidationType |
| void hpp::corbaserver::Problem::addEdgeToRoadmap | ( | in floatSeq | config1, |
| in floatSeq | config2, | ||
| in unsigned long | pathId, | ||
| in boolean | bothEdges | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Add an edge to the roadmap.
| config1 | configuration of start node, |
| config2 | configuration of destination node, |
| pathId | index of the path to store in the edge in the path vector, |
| bothEdges | whether to also insert edge from destination node to start node. |
Add goal configuration to specified problem.
| dofArray | Array of degrees of freedom |
| Error. |
| void hpp::corbaserver::Problem::addLockedJointConstraints | ( | in string | configProjName, |
| in Names_t | lockedJointNames | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Add locked joints by names in ConfigProjector
| configProjName | Name of the config projector if created by this method, |
| lockedJointNames | names of the locked joints, |
Locked joints should have been added in the ProblemSolver local map.
| void hpp::corbaserver::Problem::addNumericalConstraints | ( | in string | configProjName, |
| in Names_t | constraintNames, | ||
| in intSeq | priorities | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Add numerical constraints by names in ConfigProjector
| configProjName | Name of the config projector if created by this method, |
| constraintNames | names of the constraints to apply, |
Constraints should have been added in the ProblemSolver local map.
| void hpp::corbaserver::Problem::addPassiveDofs | ( | in string | constraintName, |
| in Names_t | jointNames | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Add vector of passive dofs into the ProblemSolver local map
| constraintName | Name of the vector of passive dofs, |
| jointNames | a sequence of joint names. |
| unsigned long hpp::corbaserver::Problem::addPath | ( | in core_idl::PathVector | _path | ) | |
| raises | ( | Error | |||
| ) | |||||
| void hpp::corbaserver::Problem::addPathOptimizer | ( | in string | pathOptimizerType | ) | |
| raises | ( | Error | |||
| ) | |||||
Add a path optimizer
| Name | of the path optimizer type, either "RandomShortcut" or any type added by core::ProblemSolver::addPathOptimizerType |
| void hpp::corbaserver::Problem::appendDirectPath | ( | in unsigned long | pathId, |
| in floatSeq | config, | ||
| in boolean | validate | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
| boolean hpp::corbaserver::Problem::applyConstraints | ( | in floatSeq | input, |
| out floatSeq | output, | ||
| out double | residualError | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Apply constaints to a configuration
constraints are stored in ProblemSolver object
| input | input configuration, |
| output | output configuration, |
| error | norm of the residual error. |
| void hpp::corbaserver::Problem::clearConfigValidations | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Clear the vector of config validations.
| void hpp::corbaserver::Problem::clearPathOptimizers | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Clear the vector of path optimizers.
| void hpp::corbaserver::Problem::clearRoadmap | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Clear the roadmap.
| void hpp::corbaserver::Problem::computeValueAndJacobian | ( | in floatSeq | config, |
| out floatSeq | value, | ||
| out floatSeqSeq | jacobian | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Compute value and Jacobian of numerical constraints
| config | input configuration |
| 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.
| void hpp::corbaserver::Problem::concatenatePath | ( | in unsigned long | startId, |
| in unsigned long | endId | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
| floatSeq hpp::corbaserver::Problem::configAtParam | ( | in unsigned long | inPathId, |
| in double | atDistance | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Get the robot config at param on a path
| inPathId | rank of the path in the problem |
| atDistance | : the user parameter choice |
| long hpp::corbaserver::Problem::connectedComponentOfEdge | ( | in unsigned long | edgeId | ) | |
| raises | ( | Error | |||
| ) | |||||
return the connected component index of the edge
| long hpp::corbaserver::Problem::connectedComponentOfNode | ( | in unsigned long | nodeId | ) | |
| raises | ( | Error | |||
| ) | |||||
return the connected component index of the node
| void hpp::corbaserver::Problem::createComBeetweenFeet | ( | in string | constraintName, |
| in string | comName, | ||
| in string | jointLName, | ||
| in string | jointRName, | ||
| in floatSeq | pointL, | ||
| in floatSeq | pointR, | ||
| in string | jointRefName, | ||
| in floatSeq | pointRef, | ||
| in boolSeq | mask | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Create ComBeetweenFeet constraint between two joints
| constraintName | name of the constraint created, |
| comName | name of a partial com computation object in problem solver map. Set "" for a full COM computation. |
| 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 |
| pointRef | point in local frame of jointRef |
| mask | Select axis to be constrained. If jointRef is "", the global frame is used. Constraints are stored in ProblemSolver object |
| core_idl::Constraint hpp::corbaserver::Problem::createConfigProjector | ( | in pinocchio_idl::Device | robot, |
| in string | name, | ||
| in double | threshold, | ||
| in unsigned long | iterations | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
| void hpp::corbaserver::Problem::createConfigurationConstraint | ( | in string | constraintName, |
| in floatSeq | goal, | ||
| in floatSeq | weights | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
| goal | configuration |
| weights | vector of weights on each DoF |
| core_idl::ConfigurationShooter hpp::corbaserver::Problem::createConfigurationShooter | ( | in string | type, |
| in core_idl::Problem | _problem | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
| core_idl::ConfigValidation hpp::corbaserver::Problem::createConfigValidation | ( | in string | type, |
| in pinocchio_idl::Device | robot | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
| core_idl::Constraint hpp::corbaserver::Problem::createConstraintSet | ( | in pinocchio_idl::Device | robot, |
| in string | name | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
| void hpp::corbaserver::Problem::createConvexShapeContactConstraint | ( | in string | constraintName, |
| in Names_t | floorJoints, | ||
| in Names_t | objectJoints, | ||
| in floatSeqSeq | pts, | ||
| in intSeqSeq | objectTriangles, | ||
| in intSeqSeq | floorTriangles | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
| core_idl::Distance hpp::corbaserver::Problem::createDistance | ( | in string | type, |
| in core_idl::Problem | _problem | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
| void hpp::corbaserver::Problem::createDistanceBetweenJointAndObjects | ( | in string | constraintName, |
| in string | joint1Name, | ||
| in Names_t | objects, | ||
| in double | distance | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
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 |
| void hpp::corbaserver::Problem::createDistanceBetweenJointConstraint | ( | in string | constraintName, |
| in string | joint1Name, | ||
| in string | joint2Name, | ||
| in double | distance | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
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 |
| void hpp::corbaserver::Problem::createIdentityConstraint | ( | in string | constraintName, |
| in Names_t | inJoints, | ||
| in Names_t | outJoints | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Create identity constraint between several joints.
| constraintName | name of the constraint created, |
| inJoints | name of the input joints, |
| outJoints | name of the output joints, Constraints are stored in ProblemSolver object |
| void hpp::corbaserver::Problem::createLockedExtraDof | ( | in string | lockedDofName, |
| in unsigned long | index, | ||
| in floatSeq | value | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
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. |
| void hpp::corbaserver::Problem::createLockedJoint | ( | in string | lockedJointName, |
| in string | jointName, | ||
| in floatSeq | value | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
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, |
| void hpp::corbaserver::Problem::createLockedJointWithComp | ( | in string | lockedJointName, |
| in string | jointName, | ||
| in floatSeq | value, | ||
| in ComparisonTypes_t | comp | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
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, |
| comp | vector if comparison types |
| void hpp::corbaserver::Problem::createManipulability | ( | in string | name, |
| in string | function | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Create a manipulatibility constraint
| name | key of the constraint in the Problem Solver map |
| function | name of the function used to get the Jacobian matrix. |
| void hpp::corbaserver::Problem::createOrientationConstraint | ( | in string | constraintName, |
| in string | joint1Name, | ||
| in string | joint2Name, | ||
| in Quaternion_ | p, | ||
| in boolSeq | mask | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
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 of joint2 is "", the corresponding joint is replaced by the global frame. constraints are stored in ProblemSolver object |
| core_idl::PathOptimizer hpp::corbaserver::Problem::createPathOptimizer | ( | in string | type, |
| in core_idl::Problem | _problem | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
| core_idl::PathPlanner hpp::corbaserver::Problem::createPathPlanner | ( | in string | type, |
| in core_idl::Problem | _problem, | ||
| in core_idl::Roadmap | roadmap | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
| core_idl::PathProjector hpp::corbaserver::Problem::createPathProjector | ( | in string | type, |
| in core_idl::Problem | robot, | ||
| in value_type | parameter | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
| core_idl::PathValidation hpp::corbaserver::Problem::createPathValidation | ( | in string | type, |
| in pinocchio_idl::Device | robot, | ||
| in value_type | parameter | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
| void hpp::corbaserver::Problem::createPositionConstraint | ( | in string | constraintName, |
| in string | joint1Name, | ||
| in string | joint2Name, | ||
| in floatSeq | point1, | ||
| in floatSeq | point2, | ||
| in boolSeq | mask | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
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 |
| core_idl::Problem hpp::corbaserver::Problem::createProblem | ( | in pinocchio_idl::Device | robot | ) | |
| raises | ( | Error | |||
| ) | |||||
| void hpp::corbaserver::Problem::createRelativeComConstraint | ( | in string | constraintName, |
| in string | comName, | ||
| in string | jointLName, | ||
| in floatSeq | point, | ||
| in boolSeq | mask | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
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 |
| core_idl::Roadmap hpp::corbaserver::Problem::createRoadmap | ( | in core_idl::Distance | distance, |
| in pinocchio_idl::Device | robot | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
| core_idl::SteeringMethod hpp::corbaserver::Problem::createSteeringMethod | ( | in string | type, |
| in core_idl::Problem | _problem | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
| void hpp::corbaserver::Problem::createTransformationConstraint | ( | in string | constraintName, |
| in string | joint1Name, | ||
| in string | joint2Name, | ||
| in Transform_ | ref, | ||
| in boolSeq | mask | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
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 with key constraintName |
| void hpp::corbaserver::Problem::createTransformationConstraint2 | ( | in string | constraintName, |
| in string | joint1Name, | ||
| in string | joint2Name, | ||
| in Transform_ | frame1, | ||
| in Transform_ | frame2, | ||
| in boolSeq | mask | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Create transformation constraint between two joints
| constraintName | name of the constraint created, |
| joint1Name | name of first joint |
| joint2Name | name of second joint |
| frame1 | desired frame in joint1 |
| frame2 | desired frame in 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 with key constraintName |
| void hpp::corbaserver::Problem::createTransformationR3xSO3Constraint | ( | in string | constraintName, |
| in string | joint1Name, | ||
| in string | joint2Name, | ||
| in Transform_ | frame1, | ||
| in Transform_ | frame2, | ||
| in boolSeq | mask | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Create transformation constraint between two joints
| constraintName | name of the constraint created, |
| joint1Name | name of first joint |
| joint2Name | name of second joint |
| frame1 | desired frame in joint1 |
| frame2 | desired frame in 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 with key constraintName |
| floatSeq hpp::corbaserver::Problem::derivativeAtParam | ( | in unsigned long | inPathId, |
| in unsigned long | orderId, | ||
| in double | atDistance | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Get the robot velocity at param on a path
| inPathId | rank of the path in the problem |
| orderId | order of the derivative |
| atDistance | : the user parameter choice |
| boolean hpp::corbaserver::Problem::directPath | ( | in floatSeq | startConfig, |
| in floatSeq | endConfig, | ||
| in boolean | validate, | ||
| out unsigned long | pathId, | ||
| out string | report | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
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. |
| pathId | returns index of copmuted path in path vector. |
| report | the reason why the config is not valid. |
| string hpp::corbaserver::Problem::displayConstraints | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Display the constraint in the ConfigProjector.
| void hpp::corbaserver::Problem::edge | ( | in unsigned long | edgeId, |
| out floatSeq | q1, | ||
| out floatSeq | q2 | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Edge at given rank.
| void hpp::corbaserver::Problem::erasePath | ( | in unsigned long | pathId | ) | |
| raises | ( | Error | |||
| ) | |||||
| boolean hpp::corbaserver::Problem::executeOneStep | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Execute one step of the planner.
| void hpp::corbaserver::Problem::extractPath | ( | in unsigned long | pathId, |
| in double | start, | ||
| in double | end | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
| void hpp::corbaserver::Problem::filterCollisionPairs | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Build matrix of relative motions between joints
See hpp::core::Problem::filterCollisionPairs.
| void hpp::corbaserver::Problem::finishSolveStepByStep | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Finish the step-by-step planning. The path optimizer is not called
| boolean hpp::corbaserver::Problem::generateValidConfig | ( | in unsigned long | maxIter, |
| out floatSeq | output, | ||
| out double | residualError | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Generate random configuration and apply constaints to a configuration
constraints are stored in ProblemSolver object The class hpp::core::BasicConfigurationShooter is used for random generation of configuration.
| maxIter | maximum number of tries, |
| output | output configuration, |
| error | norm of the residual error. |
Return a list of available elements of type type
| type | enter "type" to know what types I know of. This is case insensitive. |
| boolean hpp::corbaserver::Problem::getConstantRightHandSide | ( | in string | constraintName | ) | |
| raises | ( | Error | |||
| ) | |||||
Get whether right hand side of a numerical constraint is constant
| constraintName | Name of the numerical constraint, |
| constraints_idl::Implicit hpp::corbaserver::Problem::getConstraint | ( | in string | constraintName | ) | |
| raises | ( | Error | |||
| ) | |||||
| void hpp::corbaserver::Problem::getConstraintDimensions | ( | in string | constraintName, |
| out unsigned long | inputSize, | ||
| out unsigned long | inputDerivativeSize, | ||
| out unsigned long | outputSize, | ||
| out unsigned long | outputDerivativeSize | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Get constraint dimensions.
| core_idl::Distance hpp::corbaserver::Problem::getDistance | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
| double hpp::corbaserver::Problem::getErrorThreshold | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Get error threshold in numerical constraint resolution.
| floatSeqSeq hpp::corbaserver::Problem::getGoalConfigs | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Get goal configurations of specified problem.
Get initial configuration of specified problem.
| unsigned long hpp::corbaserver::Problem::getMaxIterPathPlanning | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Get maximal number of iterations in path planning.
| unsigned long hpp::corbaserver::Problem::getMaxIterProjection | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Set maximal number of iterations in numerical constraint resolution.
| unsigned short hpp::corbaserver::Problem::getMaxNumThreads | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
| floatSeq hpp::corbaserver::Problem::getNearestConfig | ( | in floatSeq | config, |
| in long | connectedComponentId, | ||
| out double | distance | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
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). |
| pinocchio_idl::CollisionObject hpp::corbaserver::Problem::getObstacle | ( | in string | name | ) | |
| raises | ( | Error | |||
| ) | |||||
| any hpp::corbaserver::Problem::getParameter | ( | in string | name | ) | |
| raises | ( | Error | |||
| ) | |||||
Get parameter with given name raise an exception when the parameter is not found.
| string hpp::corbaserver::Problem::getParameterDoc | ( | in string | name | ) | |
| raises | ( | Error | |||
| ) | |||||
Get parameter documentation raise an exception when the parameter is not found.
| core_idl::Path hpp::corbaserver::Problem::getPath | ( | in unsigned long | pathId | ) | |
| raises | ( | Error | |||
| ) | |||||
| core_idl::PathPlanner hpp::corbaserver::Problem::getPathPlanner | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
| core_idl::PathValidation hpp::corbaserver::Problem::getPathValidation | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
| core_idl::Problem hpp::corbaserver::Problem::getProblem | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Get right hand side of constraints in config projector.
Return a list of selected elements of type type
| type | enter "type" to know what types I know of. This is case insensitive. |
| core_idl::SteeringMethod hpp::corbaserver::Problem::getSteeringMethod | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
| double hpp::corbaserver::Problem::getTimeOutPathPlanning | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Get time out in path planning (in seconds)
| floatSeqSeq hpp::corbaserver::Problem::getWaypoints | ( | in unsigned long | pathId, |
| out floatSeq | times | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Get way points of a path
| pathId | rank of the path in the problem |
| void hpp::corbaserver::Problem::interruptPathPlanning | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Interrupt path planning activity.
| core_idl::Path hpp::corbaserver::Problem::loadPath | ( | in string | filename | ) | |
| raises | ( | Error | |||
| ) | |||||
Load a path from a file
| filename | name of the file from which the path is read. |
| boolean hpp::corbaserver::Problem::loadPlugin | ( | in string | pluginName | ) | |
| raises | ( | Error | |||
| ) | |||||
| void hpp::corbaserver::Problem::loadRoadmap | ( | in string | filename | ) | |
| raises | ( | Error | |||
| ) | |||||
Load a roadmap from a file
| filename | name of the file from which the roadmap is read. The roadmap is stored in the current ProblemSolver instance |
| void hpp::corbaserver::Problem::movePathToProblem | ( | in unsigned long | pathId, |
| in string | problemName, | ||
| in Names_t | jointNames | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Move a path from the current problem to another problem.
| problemName | the destination problem |
| jointNames | a list of joint names representing the subchain to extract from the original path. |
| floatSeqSeq hpp::corbaserver::Problem::nodes | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Nodes of the roadmap.
| floatSeqSeq hpp::corbaserver::Problem::nodesConnectedComponent | ( | in unsigned long | connectedComponentId | ) | |
| raises | ( | Error | |||
| ) | |||||
Nodes of a connected component
| connectedComponentId | index of connected component in roadmap |
| long hpp::corbaserver::Problem::numberConnectedComponents | ( | ) |
Number of connected components.
| long hpp::corbaserver::Problem::numberEdges | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Number of edges.
| long hpp::corbaserver::Problem::numberNodes | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
| long hpp::corbaserver::Problem::numberPaths | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Get Number of paths.
| boolean hpp::corbaserver::Problem::optimize | ( | in floatSeq | input, |
| out floatSeq | output, | ||
| out floatSeq | residualError | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Find a local minimum of the least priority constraints
while respecting the other priorities.
| input | input configuration, |
| output | output configuration, |
| residualError. |
Optimize a given path
| inPathId | Id of the path in this problem. |
| Error. |
| double hpp::corbaserver::Problem::pathLength | ( | in unsigned long | inPathId | ) | |
| raises | ( | Error | |||
| ) | |||||
Get length of path
| inPathId | rank of the path in the problem |
| boolean hpp::corbaserver::Problem::prepareSolveStepByStep | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Prepare the solver for a step by step planning. and try to make direct connections (call PathPlanner::tryDirectPath)
| boolean hpp::corbaserver::Problem::projectPath | ( | in unsigned long | patId | ) | |
| raises | ( | Error | |||
| ) | |||||
Apply the path projector method to the path
| core_idl::Roadmap hpp::corbaserver::Problem::readRoadmap | ( | in string | filename, |
| in pinocchio_idl::Device | robot | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Load a roadmap from a file
| filename | name of the file, If it ends with '.xml', then the file is interpreted in XML format, otherwise it is interpreted in binary format. |
| robot | the robot for which the roadmap was built before saving in the file. |
| void hpp::corbaserver::Problem::resetConstraintMap | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
| void hpp::corbaserver::Problem::resetConstraints | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Reset constraints.
| void hpp::corbaserver::Problem::resetGoalConfigs | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Reset goal configurations.
| void hpp::corbaserver::Problem::resetGoalConstraints | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Clear goal constraints.
| void hpp::corbaserver::Problem::resetProblem | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Reset the current problem.
| void hpp::corbaserver::Problem::resetRoadmap | ( | ) | ||
| raises | ( | Error | ||
| ) | ||||
Reset the roadmap This should be done when joints bounds are modified because the KDTree must be resized.
| boolean hpp::corbaserver::Problem::reversePath | ( | in unsigned long | pathId, |
| out unsigned long | reversedPathId | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Reverse a path
| void hpp::corbaserver::Problem::savePath | ( | in core_idl::Path | _path, |
| in string | filename | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Save a path to file.
| _path | the path to save. |
| filename | name of the file where the path is saved. |
| void hpp::corbaserver::Problem::saveRoadmap | ( | in string | filename | ) | |
| raises | ( | Error | |||
| ) | |||||
Save the roadmap stored in the ProblemSolver instance in a file
| filename | name of the file where the roadmap is saved |
| void hpp::corbaserver::Problem::scCreateScalarMultiply | ( | in string | outName, |
| in double | scalar, | ||
| in string | inName | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
See hpp::constraints::ScalarMultiply.
| void hpp::corbaserver::Problem::selectConfigurationShooter | ( | in string | configurationShooterType | ) | |
| raises | ( | Error | |||
| ) | |||||
Select configuration shooter type
| Name | of the configuration planner type, either "Uniform" or any type added by method core::ProblemSolver::addConfigurationShooterType |
| void hpp::corbaserver::Problem::selectDistance | ( | in string | distanceType | ) | |
| raises | ( | Error | |||
| ) | |||||
Select distance type
| Name | of the distance type, either "WeighedDistance" or any type added by method core::ProblemSolver::addDistanceType |
| void hpp::corbaserver::Problem::selectPathPlanner | ( | in string | pathPlannerType | ) | |
| raises | ( | Error | |||
| ) | |||||
Select path planner type
| Name | of the path planner type, either "DiffusingPlanner", "VisibilityPrmPlanner", or any type added by method core::ProblemSolver::addPathPlannerType |
| void hpp::corbaserver::Problem::selectPathProjector | ( | in string | pathProjectorType, |
| in double | tolerance | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Select path projector method
| Name | of the path projector method, either "None" "Progressive", "Dichotomy", or any type added by core::ProblemSolver::addPathProjectorType, |
| tolerance |
| void hpp::corbaserver::Problem::selectPathValidation | ( | in string | pathValidationType, |
| in double | tolerance | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
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. |
| boolean hpp::corbaserver::Problem::selectProblem | ( | in string | name | ) | |
| raises | ( | Error | |||
| ) | |||||
Select a problem by its name. If no problem with this name exists, a new problem is created and selected.
| name | the problem name. |
| void hpp::corbaserver::Problem::selectSteeringMethod | ( | in string | steeringMethodType | ) | |
| raises | ( | Error | |||
| ) | |||||
Select steering method type
| Name | of the steering method type, either "SteeringMethodStraight" or any type added by method core::ProblemSolver::addSteeringMethodType |
| void hpp::corbaserver::Problem::setConstantRightHandSide | ( | in string | constraintName, |
| in boolean | constant | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
(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.
| void hpp::corbaserver::Problem::setDefaultLineSearchType | ( | in string | type | ) | |
| raises | ( | Error | |||
| ) | |||||
| void hpp::corbaserver::Problem::setDistance | ( | in core_idl::Distance | distance | ) | |
| raises | ( | Error | |||
| ) | |||||
| void hpp::corbaserver::Problem::setErrorThreshold | ( | in double | threshold | ) | |
| raises | ( | Error | |||
| ) | |||||
Set error threshold in numerical constraint resolution.
Set goal as a task.
Set initial configuration of specified problem.
| dofArray | Array of degrees of freedom |
| Error. |
| void hpp::corbaserver::Problem::setMaxIterPathPlanning | ( | in unsigned long | iterations | ) | |
| raises | ( | Error | |||
| ) | |||||
Set maximal number of iterations in path planning.
| void hpp::corbaserver::Problem::setMaxIterProjection | ( | in unsigned long | iterations | ) | |
| raises | ( | Error | |||
| ) | |||||
Set maximal number of iterations in numerical constraint resolution.
| void hpp::corbaserver::Problem::setMaxNumThreads | ( | in unsigned short | n | ) | |
| raises | ( | Error | |||
| ) | |||||
| void hpp::corbaserver::Problem::setNumericalConstraintsLastPriorityOptional | ( | in boolean | optional | ) | |
| raises | ( | Error | |||
| ) | |||||
Declare last priority order as optional in the numerical constraints
| void hpp::corbaserver::Problem::setParameter | ( | in string | name, |
| in any | value | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
Set a parameter
| value | the input type must be long, double, const char* |
| void hpp::corbaserver::Problem::setRandomSeed | ( | in long | seed | ) | |
| raises | ( | Error | |||
| ) | |||||
Set random seed of random number generator.
Set right hand side of constraints in config projector
| rhs | right hand side of constraints. Contains only right hand side of non-constant constraints |
| void hpp::corbaserver::Problem::setRightHandSideByName | ( | in string | constraintName, |
| in floatSeq | rhs | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
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. |
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 |
| void hpp::corbaserver::Problem::setRightHandSideFromConfigByName | ( | in string | constraintName, |
| in floatSeq | config | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
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. |
| void hpp::corbaserver::Problem::setRobot | ( | in pinocchio_idl::Device | robot | ) | |
| raises | ( | Error | |||
| ) | |||||
| void hpp::corbaserver::Problem::setTimeOutPathPlanning | ( | in double | timeOut | ) | |
| raises | ( | Error | |||
| ) | |||||
Set time out in path planning (in seconds)
Solve the problem.
| Error. |
| void hpp::corbaserver::Problem::writeRoadmap | ( | in string | filename, |
| in core_idl::Roadmap | roadmap, | ||
| in pinocchio_idl::Device | robot | ||
| ) | |||
| raises | ( | Error | |
| ) | |||
write a roadmap to a file
| filename | name of the file, If it ends with '.xml', then the file is interpreted in XML format, otherwise it is interpreted in binary format. |
| robot | the robot for which the roadmap was built before saving in the file. |