11 #ifndef HPP_CORBASERVER_PROBLEM_SERVER_IDL 12 #define HPP_CORBASERVER_PROBLEM_SERVER_IDL 29 void setRandomSeed (in
long seed) raises (
Error);
32 void setMaxNumThreads (in
unsigned short n) raises (
Error);
35 unsigned short getMaxNumThreads () raises (
Error);
50 void setParameter (in
string name, in any value) raises (
Error);
54 any getParameter (in
string name) raises (
Error);
58 string getParameterDoc (in
string name) raises (
Error);
64 boolean selectProblem (in
string name) raises (
Error);
67 void resetProblem () raises (
Error);
70 boolean loadPlugin (in
string pluginName) raises (
Error);
77 void movePathToProblem (in
unsigned long pathId, in
string problemName,
102 void resetGoalConfigs () raises (
Error);
105 void setGoalConstraints(in
Names_t constraints) raises(
Error);
108 void resetGoalConstraints() raises(
Error);
122 out
double residualError)
156 boolean generateValidConfig (in
unsigned long maxIter, out
floatSeq output,
157 out
double residualError)
171 void createOrientationConstraint
172 (in
string constraintName, in
string joint1Name,
187 void createTransformationConstraint
188 (in
string constraintName, in
string joint1Name,
194 void createTransformationR3xSO3Constraint
195 (in
string constraintName, in
string joint1Name, in
string joint2Name,
209 void createTransformationConstraint2
210 (in
string constraintName, in
string joint1Name,
218 void createLockedJoint (in
string lockedJointName,
227 void createLockedJointWithComp (in
string lockedJointName,
238 void createLockedExtraDof (in
string lockedDofName,
239 in
unsigned long index,
245 void createManipulability (in
string name,
246 in
string function) raises (
Error);
262 void createComBeetweenFeet (in
string constraintName, in
string comName,
263 in
string jointLName, in
string jointRName, in
floatSeq pointL,
277 void createRelativeComConstraint (in
string constraintName, in
string comName,
281 void createConvexShapeContactConstraint
282 (in
string constraintName, in
Names_t floorJoints, in
Names_t objectJoints,
297 void createPositionConstraint (in
string constraintName,
298 in
string joint1Name,
299 in
string joint2Name,
307 void createConfigurationConstraint (in
string constraintName,
320 void createDistanceBetweenJointConstraint
321 (in
string constraintName, in
string joint1Name, in
string joint2Name,
322 in
double distance) raises (
Error);
331 void createDistanceBetweenJointAndObjects
332 (in
string constraintName, in
string joint1Name, in
Names_t objects,
333 in
double distance) raises (
Error);
342 void createIdentityConstraint
343 (in
string constraintName, in
Names_t inJoints, in
Names_t outJoints)
347 void resetConstraints () raises (
Error);
350 void resetConstraintMap () raises (
Error);
355 void addPassiveDofs (in
string constraintName, in
Names_t jointNames)
359 void getConstraintDimensions (in
string constraintName,
360 out
unsigned long inputSize , out
unsigned long inputDerivativeSize,
361 out
unsigned long outputSize, out
unsigned long outputDerivativeSize)
370 void setConstantRightHandSide (in
string constraintName,
377 boolean getConstantRightHandSide (in
string constraintName)
394 void setRightHandSideFromConfig (in
floatSeq config) raises (
Error);
400 void setRightHandSideByName (in
string constraintName, in
floatSeq rhs)
407 void setRightHandSideFromConfigByName (in
string constraintName, in
floatSeq config)
416 void addNumericalConstraints (in
string configProjName,
424 void setNumericalConstraintsLastPriorityOptional (in
boolean optional)
433 void addLockedJointConstraints (in
string configProjName,
437 string displayConstraints () raises (
Error);
440 double getErrorThreshold () raises (
Error);
443 void setErrorThreshold (in
double threshold) raises (
Error);
445 void setDefaultLineSearchType (in
string type) raises (
Error);
448 unsigned long getMaxIterProjection () raises (
Error);
451 void setMaxIterProjection (in
unsigned long iterations) raises (
Error);
454 unsigned long getMaxIterPathPlanning () raises (
Error);
457 void setMaxIterPathPlanning (in
unsigned long iterations) raises (
Error);
463 void scCreateScalarMultiply (in
string outName, in
double scalar, in
string inName) raises (
Error);
466 double getTimeOutPathPlanning () raises (
Error);
469 void setTimeOutPathPlanning (in
double timeOut) raises (
Error);
481 void filterCollisionPairs () raises (
Error);
492 void selectPathPlanner (in
string pathPlannerType) raises (
Error);
498 void selectConfigurationShooter (in
string configurationShooterType) raises (
Error);
504 void selectDistance (in
string distanceType) raises (
Error);
511 void selectSteeringMethod (in
string steeringMethodType) raises (
Error);
516 void addPathOptimizer (in
string pathOptimizerType) raises (
Error);
519 void clearPathOptimizers () raises (
Error);
525 void addConfigValidation (in
string configValidationType) raises (
Error);
528 void clearConfigValidations () raises (
Error);
535 void selectPathValidation (in
string pathValidationType,
536 in
double tolerance) raises (
Error);
543 void selectPathProjector (in
string pathProjectorType,
544 in
double tolerance) raises (
Error);
549 boolean prepareSolveStepByStep () raises (
Error);
555 boolean executeOneStep () raises (
Error);
559 void finishSolveStepByStep () raises (
Error);
577 out
unsigned long pathId, out
string report)
582 boolean reversePath (in
unsigned long pathId, out
unsigned long reversedPathId)
601 in
unsigned long pathId, in
boolean bothEdges)
605 void appendDirectPath (in
unsigned long pathId, in
floatSeq config, in
boolean validate)
609 void concatenatePath (in
unsigned long startId, in
unsigned long endId)
613 void extractPath (in
unsigned long pathId, in
double start, in
double end)
617 void erasePath (in
unsigned long pathId)
622 boolean projectPath (in
unsigned long patId) raises (
Error);
625 long numberPaths () raises (
Error);
632 intSeq optimizePath(in
unsigned long inPathId) raises (
Error);
637 double pathLength(in
unsigned long inPathId) raises (
Error);
643 floatSeq configAtParam(in
unsigned long inPathId, in
double atDistance)
651 floatSeq derivativeAtParam(in
unsigned long inPathId, in
unsigned long orderId, in
double atDistance)
667 void interruptPathPlanning() raises (
Error);
677 long numberNodes() raises (
Error);
683 long connectedComponentOfEdge(in
unsigned long edgeId) raises(
Error);
686 long connectedComponentOfNode(in
unsigned long nodeId) raises(
Error);
689 long numberEdges () raises (
Error);
696 long numberConnectedComponents ();
701 floatSeqSeq nodesConnectedComponent (in
unsigned long connectedComponentId)
710 floatSeq getNearestConfig(in
floatSeq config, in
long connectedComponentId, out
double distance)
714 void clearRoadmap () raises (
Error);
719 void resetRoadmap () raises (
Error);
724 void saveRoadmap (in
string filename) raises (
Error);
730 void loadRoadmap (in
string filename) raises (
Error);
778 void writeRoadmap(in
string filename,
Definition: configuration_shooters.idl:20
Definition: path_planners.idl:37
Definition: robots.idl:28
Definition: path_planners.idl:86
Definition: common-idl.hh:461
Implement CORBA interface ``Obstacle''.
Definition: basic-server.hh:35
double value_type
Definition: common.idl:18
Definition: robots.idl:109
Definition: constraints.idl:40
Definition: distances.idl:19
Corba exception travelling through the Corba channel.
Definition: common.idl:26
Definition: path_validations.idl:63
::CORBA::Double Transform_[7]
Definition: common-idl.hh:915
::CORBA::Double Quaternion_[4]
Definition: common-idl.hh:1077
Definition: path_planners.idl:114
Definition: common-idl.hh:78
Definition: common-idl.hh:803
Definition: common-idl.hh:347
Definition: steering_methods.idl:22
Definition: common-idl.hh:1138
Definition: common-idl.hh:575
Definition: _problem.idl:31
To define and solve a path planning problem.
Definition: problem.idl:26
Definition: common-idl.hh:689
Definition: path_validations.idl:30