hpp-corbaserver 6.0.0
Corba server for Humanoid Path Planner applications
Loading...
Searching...
No Matches
hpp::corbaserver::Problem Interface Reference

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)
 

Detailed Description

To define and solve a path planning problem.

Member Function Documentation

◆ addConfigToRoadmap()

void hpp::corbaserver::Problem::addConfigToRoadmap ( in floatSeq  config)
raises (Error
)

add a configuration to a roadmap

Parameters
configConfiguration to add

A node is created if necessary.

◆ addConfigValidation()

void hpp::corbaserver::Problem::addConfigValidation ( in string  configValidationType)
raises (Error
)

Add a config validation

Parameters
Nameof the config validation type, either "CollisionValidation" or "JointBoundValidation" or any type added by core::ProblemSolver::addConfigValidationType

◆ addEdgeToRoadmap()

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.

Parameters
config1configuration of start node,
config2configuration of destination node,
pathIdindex of the path to store in the edge in the path vector,
bothEdgeswhether to also insert edge from destination node to start node.
See also
hpp::core::ProblemSolver::addEdgeToRoadmap.

◆ addGoalConfig()

void hpp::corbaserver::Problem::addGoalConfig ( in floatSeq  dofArray)
raises (Error
)

Add goal configuration to specified problem.

Parameters
dofArrayArray of degrees of freedom
Exceptions
Error.

◆ addLockedJointConstraints()

void hpp::corbaserver::Problem::addLockedJointConstraints ( in string  configProjName,
in Names_t  lockedJointNames 
)
raises (Error
)

Add locked joints by names in ConfigProjector

Parameters
configProjNameName of the config projector if created by this method,
lockedJointNamesnames of the locked joints,

Locked joints should have been added in the ProblemSolver local map.

◆ addNumericalConstraints()

void hpp::corbaserver::Problem::addNumericalConstraints ( in string  configProjName,
in Names_t  constraintNames,
in intSeq  priorities 
)
raises (Error
)

Add numerical constraints by names in ConfigProjector

Parameters
configProjNameName of the config projector if created by this method,
constraintNamesnames of the constraints to apply,

Constraints should have been added in the ProblemSolver local map.

◆ addPassiveDofs()

void hpp::corbaserver::Problem::addPassiveDofs ( in string  constraintName,
in Names_t  jointNames 
)
raises (Error
)

Add vector of passive dofs into the ProblemSolver local map

Parameters
constraintNameName of the vector of passive dofs,
jointNamesa sequence of joint names.

◆ addPath()

unsigned long hpp::corbaserver::Problem::addPath ( in core_idl::PathVector  _path)
raises (Error
)

◆ addPathOptimizer()

void hpp::corbaserver::Problem::addPathOptimizer ( in string  pathOptimizerType)
raises (Error
)

Add a path optimizer

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

◆ appendDirectPath()

void hpp::corbaserver::Problem::appendDirectPath ( in unsigned long  pathId,
in floatSeq  config,
in boolean  validate 
)
raises (Error
)

◆ applyConstraints()

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

Parameters
inputinput configuration,
Return values
outputoutput configuration,
errornorm of the residual error.

◆ clearConfigValidations()

void hpp::corbaserver::Problem::clearConfigValidations ( )
raises (Error
)

Clear the vector of config validations.

◆ clearPathOptimizers()

void hpp::corbaserver::Problem::clearPathOptimizers ( )
raises (Error
)

Clear the vector of path optimizers.

◆ clearRoadmap()

void hpp::corbaserver::Problem::clearRoadmap ( )
raises (Error
)

Clear the roadmap.

◆ computeValueAndJacobian()

void hpp::corbaserver::Problem::computeValueAndJacobian ( in floatSeq  config,
out floatSeq  value,
out floatSeqSeq  jacobian 
)
raises (Error
)

Compute value and Jacobian of numerical constraints

Parameters
configinput configuration
Return values
valuevalues of the numerical constraints stacked in a unique vector,
Jacobianof the numerical constraints stacked in a unique matrix.

Columns of the Jacobian corresponding to locked joints are omitted, columns corresponding to passive dofs are set to 0.

◆ concatenatePath()

void hpp::corbaserver::Problem::concatenatePath ( in unsigned long  startId,
in unsigned long  endId 
)
raises (Error
)

◆ configAtParam()

floatSeq hpp::corbaserver::Problem::configAtParam ( in unsigned long  inPathId,
in double  atDistance 
)
raises (Error
)

Get the robot config at param on a path

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

◆ connectedComponentOfEdge()

long hpp::corbaserver::Problem::connectedComponentOfEdge ( in unsigned long  edgeId)
raises (Error
)

return the connected component index of the edge

◆ connectedComponentOfNode()

long hpp::corbaserver::Problem::connectedComponentOfNode ( in unsigned long  nodeId)
raises (Error
)

return the connected component index of the node

◆ createComBeetweenFeet()

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

Parameters
constraintNamename of the constraint created,
comNamename of a partial com computation object in problem solver map. Set "" for a full COM computation.
jointLNamename of first joint
jointRNamename of second joint
pointLpoint in local frame of jointL.
pointRpoint in local frame of jointR.
jointRefNamename of second joint
pointRefpoint in local frame of jointRef
maskSelect axis to be constrained. If jointRef is "", the global frame is used. Constraints are stored in ProblemSolver object

◆ createConfigProjector()

core_idl::Constraint hpp::corbaserver::Problem::createConfigProjector ( in pinocchio_idl::Device  robot,
in string  name,
in double  threshold,
in unsigned long  iterations 
)
raises (Error
)

◆ createConfigurationConstraint()

void hpp::corbaserver::Problem::createConfigurationConstraint ( in string  constraintName,
in floatSeq  goal,
in floatSeq  weights 
)
raises (Error
)
Parameters
goalconfiguration
weightsvector of weights on each DoF

◆ createConfigurationShooter()

core_idl::ConfigurationShooter hpp::corbaserver::Problem::createConfigurationShooter ( in string  type,
in core_idl::Problem  _problem 
)
raises (Error
)

◆ createConfigValidation()

core_idl::ConfigValidation hpp::corbaserver::Problem::createConfigValidation ( in string  type,
in pinocchio_idl::Device  robot 
)
raises (Error
)

◆ createConstraintSet()

core_idl::Constraint hpp::corbaserver::Problem::createConstraintSet ( in pinocchio_idl::Device  robot,
in string  name 
)
raises (Error
)

◆ createConvexShapeContactConstraint()

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
)

◆ createDistance()

core_idl::Distance hpp::corbaserver::Problem::createDistance ( in string  type,
in core_idl::Problem  _problem 
)
raises (Error
)

◆ createDistanceBetweenJointAndObjects()

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

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

◆ createDistanceBetweenJointConstraint()

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

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

◆ createIdentityConstraint()

void hpp::corbaserver::Problem::createIdentityConstraint ( in string  constraintName,
in Names_t  inJoints,
in Names_t  outJoints 
)
raises (Error
)

Create identity constraint between several joints.

Parameters
constraintNamename of the constraint created,
inJointsname of the input joints,
outJointsname of the output joints, Constraints are stored in ProblemSolver object
See also
hpp::constraints::Identity

◆ createLockedExtraDof()

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

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

◆ createLockedJoint()

void hpp::corbaserver::Problem::createLockedJoint ( in string  lockedJointName,
in string  jointName,
in floatSeq  value 
)
raises (Error
)

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,

◆ createLockedJointWithComp()

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

Parameters
lockedJointNamekey of the constraint in the ProblemSolver map,
jointNamename of the joint,
valuevalue of the joint configuration,
compvector if comparison types

◆ createManipulability()

void hpp::corbaserver::Problem::createManipulability ( in string  name,
in string  function 
)
raises (Error
)

Create a manipulatibility constraint

Parameters
namekey of the constraint in the Problem Solver map
functionname of the function used to get the Jacobian matrix.

◆ createOrientationConstraint()

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

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

◆ createPathOptimizer()

core_idl::PathOptimizer hpp::corbaserver::Problem::createPathOptimizer ( in string  type,
in core_idl::Problem  _problem 
)
raises (Error
)

◆ createPathPlanner()

core_idl::PathPlanner hpp::corbaserver::Problem::createPathPlanner ( in string  type,
in core_idl::Problem  _problem,
in core_idl::Roadmap  roadmap 
)
raises (Error
)

◆ createPathProjector()

core_idl::PathProjector hpp::corbaserver::Problem::createPathProjector ( in string  type,
in core_idl::Problem  robot,
in value_type  parameter 
)
raises (Error
)

◆ createPathValidation()

core_idl::PathValidation hpp::corbaserver::Problem::createPathValidation ( in string  type,
in pinocchio_idl::Device  robot,
in value_type  parameter 
)
raises (Error
)

◆ createPositionConstraint()

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

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

◆ createProblem()

core_idl::Problem hpp::corbaserver::Problem::createProblem ( in pinocchio_idl::Device  robot)
raises (Error
)

◆ createRelativeComConstraint()

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

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

◆ createRoadmap()

core_idl::Roadmap hpp::corbaserver::Problem::createRoadmap ( in core_idl::Distance  distance,
in pinocchio_idl::Device  robot 
)
raises (Error
)

◆ createSteeringMethod()

core_idl::SteeringMethod hpp::corbaserver::Problem::createSteeringMethod ( in string  type,
in core_idl::Problem  _problem 
)
raises (Error
)

◆ createTransformationConstraint()

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

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 with key constraintName

◆ createTransformationConstraint2()

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

Parameters
constraintNamename of the constraint created,
joint1Namename of first joint
joint2Namename of second joint
frame1desired frame in joint1
frame2desired frame in 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 with key constraintName

◆ createTransformationR3xSO3Constraint()

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

Parameters
constraintNamename of the constraint created,
joint1Namename of first joint
joint2Namename of second joint
frame1desired frame in joint1
frame2desired frame in 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 with key constraintName
Note
the function outputs an element of R3xSO3

◆ derivativeAtParam()

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

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

◆ directPath()

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

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.
Return values
pathIdreturns index of copmuted path in path vector.
reportthe reason why the config is not valid.
Returns
TRUE if created path is fully valid.

◆ displayConstraints()

string hpp::corbaserver::Problem::displayConstraints ( )
raises (Error
)

Display the constraint in the ConfigProjector.

◆ edge()

void hpp::corbaserver::Problem::edge ( in unsigned long  edgeId,
out floatSeq  q1,
out floatSeq  q2 
)
raises (Error
)

Edge at given rank.

◆ erasePath()

void hpp::corbaserver::Problem::erasePath ( in unsigned long  pathId)
raises (Error
)

◆ executeOneStep()

boolean hpp::corbaserver::Problem::executeOneStep ( )
raises (Error
)

Execute one step of the planner.

Returns
True if a path has been found.
Note
This won't check if a solution has been found before doing one step. The decision to stop planning is let to the user.

◆ extractPath()

void hpp::corbaserver::Problem::extractPath ( in unsigned long  pathId,
in double  start,
in double  end 
)
raises (Error
)

◆ filterCollisionPairs()

void hpp::corbaserver::Problem::filterCollisionPairs ( )
raises (Error
)

Build matrix of relative motions between joints

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

◆ finishSolveStepByStep()

void hpp::corbaserver::Problem::finishSolveStepByStep ( )
raises (Error
)

Finish the step-by-step planning. The path optimizer is not called

◆ generateValidConfig()

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.

Parameters
maxItermaximum number of tries,
Return values
outputoutput configuration,
errornorm of the residual error.

◆ getAvailable()

Names_t hpp::corbaserver::Problem::getAvailable ( in string  type)
raises (Error
)

Return a list of available elements of type type

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

◆ getConstantRightHandSide()

boolean hpp::corbaserver::Problem::getConstantRightHandSide ( in string  constraintName)
raises (Error
)

Get whether right hand side of a numerical constraint is constant

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

◆ getConstraint()

constraints_idl::Implicit hpp::corbaserver::Problem::getConstraint ( in string  constraintName)
raises (Error
)

◆ getConstraintDimensions()

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.

◆ getDistance()

core_idl::Distance hpp::corbaserver::Problem::getDistance ( )
raises (Error
)

◆ getErrorThreshold()

double hpp::corbaserver::Problem::getErrorThreshold ( )
raises (Error
)

Get error threshold in numerical constraint resolution.

◆ getGoalConfigs()

floatSeqSeq hpp::corbaserver::Problem::getGoalConfigs ( )
raises (Error
)

Get goal configurations of specified problem.

Returns
Array of degrees of freedom

◆ getInitialConfig()

floatSeq hpp::corbaserver::Problem::getInitialConfig ( )
raises (Error
)

Get initial configuration of specified problem.

Returns
Array of degrees of freedom

◆ getMaxIterPathPlanning()

unsigned long hpp::corbaserver::Problem::getMaxIterPathPlanning ( )
raises (Error
)

Get maximal number of iterations in path planning.

◆ getMaxIterProjection()

unsigned long hpp::corbaserver::Problem::getMaxIterProjection ( )
raises (Error
)

Set maximal number of iterations in numerical constraint resolution.

◆ getMaxNumThreads()

unsigned short hpp::corbaserver::Problem::getMaxNumThreads ( )
raises (Error
)

◆ getNearestConfig()

floatSeq hpp::corbaserver::Problem::getNearestConfig ( in floatSeq  config,
in long  connectedComponentId,
out double  distance 
)
raises (Error
)

Return nearest neighbour of given input configuration.

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

◆ getObstacle()

pinocchio_idl::CollisionObject hpp::corbaserver::Problem::getObstacle ( in string  name)
raises (Error
)

◆ getParameter()

any hpp::corbaserver::Problem::getParameter ( in string  name)
raises (Error
)

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

◆ getParameterDoc()

string hpp::corbaserver::Problem::getParameterDoc ( in string  name)
raises (Error
)

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

◆ getPath()

core_idl::Path hpp::corbaserver::Problem::getPath ( in unsigned long  pathId)
raises (Error
)

◆ getPathPlanner()

core_idl::PathPlanner hpp::corbaserver::Problem::getPathPlanner ( )
raises (Error
)

◆ getPathValidation()

core_idl::PathValidation hpp::corbaserver::Problem::getPathValidation ( )
raises (Error
)

◆ getProblem()

core_idl::Problem hpp::corbaserver::Problem::getProblem ( )
raises (Error
)

◆ getRightHandSide()

floatSeq hpp::corbaserver::Problem::getRightHandSide ( )
raises (Error
)

Get right hand side of constraints in config projector.

◆ getSelected()

Names_t hpp::corbaserver::Problem::getSelected ( in string  type)
raises (Error
)

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.

◆ getSteeringMethod()

core_idl::SteeringMethod hpp::corbaserver::Problem::getSteeringMethod ( )
raises (Error
)

◆ getTimeOutPathPlanning()

double hpp::corbaserver::Problem::getTimeOutPathPlanning ( )
raises (Error
)

Get time out in path planning (in seconds)

◆ getWaypoints()

floatSeqSeq hpp::corbaserver::Problem::getWaypoints ( in unsigned long  pathId,
out floatSeq  times 
)
raises (Error
)

Get way points of a path

Parameters
pathIdrank of the path in the problem

◆ interruptPathPlanning()

void hpp::corbaserver::Problem::interruptPathPlanning ( )
raises (Error
)

Interrupt path planning activity.

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

◆ loadPath()

core_idl::Path hpp::corbaserver::Problem::loadPath ( in string  filename)
raises (Error
)

Load a path from a file

Parameters
filenamename of the file from which the path is read.
Note
the file in binary format.

◆ loadPlugin()

boolean hpp::corbaserver::Problem::loadPlugin ( in string  pluginName)
raises (Error
)

◆ loadRoadmap()

void hpp::corbaserver::Problem::loadRoadmap ( in string  filename)
raises (Error
)

Load a roadmap from a file

Parameters
filenamename of the file from which the roadmap is read. The roadmap is stored in the current ProblemSolver instance
Note
the file in binary format.

◆ movePathToProblem()

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.

Parameters
problemNamethe destination problem
jointNamesa list of joint names representing the subchain to extract from the original path.
Todo:
the configuration parameter can be selected but not reorganized.

◆ node()

floatSeq hpp::corbaserver::Problem::node ( in unsigned long  nodeId)
raises (Error
)

◆ nodes()

floatSeqSeq hpp::corbaserver::Problem::nodes ( )
raises (Error
)

Nodes of the roadmap.

◆ nodesConnectedComponent()

floatSeqSeq hpp::corbaserver::Problem::nodesConnectedComponent ( in unsigned long  connectedComponentId)
raises (Error
)

Nodes of a connected component

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

◆ numberConnectedComponents()

long hpp::corbaserver::Problem::numberConnectedComponents ( )

Number of connected components.

◆ numberEdges()

long hpp::corbaserver::Problem::numberEdges ( )
raises (Error
)

Number of edges.

◆ numberNodes()

long hpp::corbaserver::Problem::numberNodes ( )
raises (Error
)

◆ numberPaths()

long hpp::corbaserver::Problem::numberPaths ( )
raises (Error
)

Get Number of paths.

◆ optimize()

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.

Parameters
inputinput configuration,
Return values
outputoutput configuration,
residualError.

◆ optimizePath()

intSeq hpp::corbaserver::Problem::optimizePath ( in unsigned long  inPathId)
raises (Error
)

Optimize a given path

Parameters
inPathIdId of the path in this problem.
Returns
the running time as 4 integers repectively representing the number of hours, minutes, seconds, microseconds.
Exceptions
Error.

◆ pathLength()

double hpp::corbaserver::Problem::pathLength ( in unsigned long  inPathId)
raises (Error
)

Get length of path

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

◆ prepareSolveStepByStep()

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)

Returns
True if a direct connection has been found.

◆ projectPath()

boolean hpp::corbaserver::Problem::projectPath ( in unsigned long  patId)
raises (Error
)

Apply the path projector method to the path

Returns
true in case of success.

◆ readRoadmap()

core_idl::Roadmap hpp::corbaserver::Problem::readRoadmap ( in string  filename,
in pinocchio_idl::Device  robot 
)
raises (Error
)

Load a roadmap from a file

Parameters
filenamename of the file, If it ends with '.xml', then the file is interpreted in XML format, otherwise it is interpreted in binary format.
robotthe robot for which the roadmap was built before saving in the file.
Returns
the roadmap as a CORBA object.

◆ resetConstraintMap()

void hpp::corbaserver::Problem::resetConstraintMap ( )
raises (Error
)

◆ resetConstraints()

void hpp::corbaserver::Problem::resetConstraints ( )
raises (Error
)

Reset constraints.

◆ resetGoalConfigs()

void hpp::corbaserver::Problem::resetGoalConfigs ( )
raises (Error
)

Reset goal configurations.

◆ resetGoalConstraints()

void hpp::corbaserver::Problem::resetGoalConstraints ( )
raises (Error
)

Clear goal constraints.

◆ resetProblem()

void hpp::corbaserver::Problem::resetProblem ( )
raises (Error
)

Reset the current problem.

◆ resetRoadmap()

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.

◆ reversePath()

boolean hpp::corbaserver::Problem::reversePath ( in unsigned long  pathId,
out unsigned long  reversedPathId 
)
raises (Error
)

Reverse a path

Returns
TRUE if created path is fully valid.

◆ savePath()

void hpp::corbaserver::Problem::savePath ( in core_idl::Path  _path,
in string  filename 
)
raises (Error
)

Save a path to file.

Parameters
_paththe path to save.
filenamename of the file where the path is saved.
Note
the file in binary format.

◆ saveRoadmap()

void hpp::corbaserver::Problem::saveRoadmap ( in string  filename)
raises (Error
)

Save the roadmap stored in the ProblemSolver instance in a file

Parameters
filenamename of the file where the roadmap is saved
Note
the file in binary format.

◆ scCreateScalarMultiply()

void hpp::corbaserver::Problem::scCreateScalarMultiply ( in string  outName,
in double  scalar,
in string  inName 
)
raises (Error
)

See hpp::constraints::ScalarMultiply.

◆ selectConfigurationShooter()

void hpp::corbaserver::Problem::selectConfigurationShooter ( in string  configurationShooterType)
raises (Error
)

Select configuration shooter type

Parameters
Nameof the configuration planner type, either "Uniform" or any type added by method core::ProblemSolver::addConfigurationShooterType

◆ selectDistance()

void hpp::corbaserver::Problem::selectDistance ( in string  distanceType)
raises (Error
)

Select distance type

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

◆ selectPathPlanner()

void hpp::corbaserver::Problem::selectPathPlanner ( in string  pathPlannerType)
raises (Error
)

Select path planner type

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

◆ selectPathProjector()

void hpp::corbaserver::Problem::selectPathProjector ( in string  pathProjectorType,
in double  tolerance 
)
raises (Error
)

Select path projector method

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

◆ selectPathValidation()

void hpp::corbaserver::Problem::selectPathValidation ( in string  pathValidationType,
in double  tolerance 
)
raises (Error
)

Select path validation method

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

◆ selectProblem()

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.

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

◆ selectSteeringMethod()

void hpp::corbaserver::Problem::selectSteeringMethod ( in string  steeringMethodType)
raises (Error
)

Select steering method type

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

◆ setConstantRightHandSide()

void hpp::corbaserver::Problem::setConstantRightHandSide ( in string  constraintName,
in boolean  constant 
)
raises (Error
)

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

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

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

◆ setDefaultLineSearchType()

void hpp::corbaserver::Problem::setDefaultLineSearchType ( in string  type)
raises (Error
)

◆ setDistance()

void hpp::corbaserver::Problem::setDistance ( in core_idl::Distance  distance)
raises (Error
)

◆ setErrorThreshold()

void hpp::corbaserver::Problem::setErrorThreshold ( in double  threshold)
raises (Error
)

Set error threshold in numerical constraint resolution.

◆ setGoalConstraints()

void hpp::corbaserver::Problem::setGoalConstraints ( in Names_t  constraints)
raises (Error
)

Set goal as a task.

◆ setInitialConfig()

void hpp::corbaserver::Problem::setInitialConfig ( in floatSeq  dofArray)
raises (Error
)

Set initial configuration of specified problem.

Parameters
dofArrayArray of degrees of freedom
Exceptions
Error.

◆ setMaxIterPathPlanning()

void hpp::corbaserver::Problem::setMaxIterPathPlanning ( in unsigned long  iterations)
raises (Error
)

Set maximal number of iterations in path planning.

◆ setMaxIterProjection()

void hpp::corbaserver::Problem::setMaxIterProjection ( in unsigned long  iterations)
raises (Error
)

Set maximal number of iterations in numerical constraint resolution.

◆ setMaxNumThreads()

void hpp::corbaserver::Problem::setMaxNumThreads ( in unsigned short  n)
raises (Error
)

◆ setNumericalConstraintsLastPriorityOptional()

void hpp::corbaserver::Problem::setNumericalConstraintsLastPriorityOptional ( in boolean  optional)
raises (Error
)

Declare last priority order as optional in the numerical constraints

◆ setParameter()

void hpp::corbaserver::Problem::setParameter ( in string  name,
in any  value 
)
raises (Error
)

Set a parameter

Parameters
valuethe input type must be long, double, const char*

◆ setRandomSeed()

void hpp::corbaserver::Problem::setRandomSeed ( in long  seed)
raises (Error
)

Set random seed of random number generator.

◆ setRightHandSide()

void hpp::corbaserver::Problem::setRightHandSide ( in floatSeq  rhs)
raises (Error
)

Set right hand side of constraints in config projector

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

◆ setRightHandSideByName()

void hpp::corbaserver::Problem::setRightHandSideByName ( in string  constraintName,
in floatSeq  rhs 
)
raises (Error
)

Set right hand side of given constraint in config projector

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

◆ setRightHandSideFromConfig()

void hpp::corbaserver::Problem::setRightHandSideFromConfig ( in floatSeq  config)
raises (Error
)

Set right hand side of constraints in config projector

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

◆ setRightHandSideFromConfigByName()

void hpp::corbaserver::Problem::setRightHandSideFromConfigByName ( in string  constraintName,
in floatSeq  config 
)
raises (Error
)

Set right hand side of given constraint in config projector

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

◆ setRobot()

void hpp::corbaserver::Problem::setRobot ( in pinocchio_idl::Device  robot)
raises (Error
)

◆ setTimeOutPathPlanning()

void hpp::corbaserver::Problem::setTimeOutPathPlanning ( in double  timeOut)
raises (Error
)

Set time out in path planning (in seconds)

◆ solve()

intSeq hpp::corbaserver::Problem::solve ( )
raises (Error
)

Solve the problem.

Returns
the running time as 4 integers repectively representing the number of hours, minutes, seconds, microseconds.
Exceptions
Error.

◆ writeRoadmap()

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

Parameters
filenamename of the file, If it ends with '.xml', then the file is interpreted in XML format, otherwise it is interpreted in binary format.
robotthe robot for which the roadmap was built before saving in the file.
Returns
the roadmap as a CORBA object.

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