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);
77 void movePathToProblem (in
unsigned long pathId, in
string problemName,
102 void resetGoalConfigs () raises (
Error);
116 out
double residualError)
150 boolean generateValidConfig (in
unsigned long maxIter, out
floatSeq output,
151 out
double residualError)
165 void createOrientationConstraint
166 (in
string constraintName, in
string joint1Name,
181 void createTransformationConstraint
182 (in
string constraintName, in
string joint1Name,
188 void createTransformationSE3Constraint
189 (in
string constraintName, in
string joint1Name, in
string joint2Name,
203 void createTransformationConstraint2
204 (in
string constraintName, in
string joint1Name,
212 void createLockedJoint (in
string lockedJointName,
222 void createLockedExtraDof (in
string lockedDofName,
223 in
unsigned long index,
229 void createManipulability (in
string name,
230 in
string function) raises (
Error);
246 void createComBeetweenFeet (in
string constraintName, in
string comName,
247 in
string jointLName, in
string jointRName, in
floatSeq pointL,
261 void createRelativeComConstraint (in
string constraintName, in
string comName,
265 void createConvexShapeContactConstraint
266 (in
string constraintName, in
Names_t floorJoints, in
Names_t objectJoints,
270 void createStaticStabilityConstraint (in
string constraintName,
272 in
string comRootJointName)
286 void createPositionConstraint (in
string constraintName,
287 in
string joint1Name,
288 in
string joint2Name,
296 void createConfigurationConstraint (in
string constraintName,
309 void createDistanceBetweenJointConstraint
310 (in
string constraintName, in
string joint1Name, in
string joint2Name,
320 void createDistanceBetweenJointAndObjects
321 (in
string constraintName, in
string joint1Name, in
Names_t objects,
322 in
double distance) raises (
Error);
331 void createIdentityConstraint
332 (in
string constraintName, in
Names_t inJoints, in
Names_t outJoints)
336 void resetConstraints () raises (
Error);
339 void resetConstraintMap () raises (
Error);
344 void addPassiveDofs (in
string constraintName, in
Names_t jointNames)
348 void getConstraintDimensions (in
string constraintName,
349 out
unsigned long inputSize , out
unsigned long inputDerivativeSize,
350 out
unsigned long outputSize, out
unsigned long outputDerivativeSize)
359 void setConstantRightHandSide (in
string constraintName,
366 boolean getConstantRightHandSide (in
string constraintName)
383 void setRightHandSideFromConfig (in
floatSeq config) raises (
Error);
389 void setRightHandSideByName (in
string constraintName, in
floatSeq rhs)
396 void setRightHandSideFromConfigByName (in
string constraintName, in
floatSeq config)
405 void addNumericalConstraints (in
string configProjName,
413 void setNumericalConstraintsLastPriorityOptional (in
boolean optional)
422 void addLockedJointConstraints (in
string configProjName,
426 string displayConstraints () raises (
Error);
429 double getErrorThreshold () raises (
Error);
432 void setErrorThreshold (in
double threshold) raises (
Error);
434 void setDefaultLineSearchType (in
string type) raises (
Error);
437 unsigned long getMaxIterProjection () raises (
Error);
440 void setMaxIterProjection (in
unsigned long iterations) raises (
Error);
443 unsigned long getMaxIterPathPlanning () raises (
Error);
446 void setMaxIterPathPlanning (in
unsigned long iterations) raises (
Error);
452 void scCreateScalarMultiply (in
string outName, in
double scalar, in
string inName) raises (
Error);
455 double getTimeOutPathPlanning () raises (
Error);
458 void setTimeOutPathPlanning (in
double timeOut) raises (
Error);
470 void filterCollisionPairs () raises (
Error);
481 void selectPathPlanner (in
string pathPlannerType) raises (
Error);
487 void selectConfigurationShooter (in
string configurationShooterType) raises (
Error);
493 void selectDistance (in
string distanceType) raises (
Error);
500 void selectSteeringMethod (in
string steeringMethodType) raises (
Error);
505 void addPathOptimizer (in
string pathOptimizerType) raises (
Error);
508 void clearPathOptimizers () raises (
Error);
514 void addConfigValidation (in
string configValidationType) raises (
Error);
517 void clearConfigValidations () raises (
Error);
524 void selectPathValidation (in
string pathValidationType,
525 in
double tolerance) raises (
Error);
532 void selectPathProjector (in
string pathProjectorType,
533 in
double tolerance) raises (
Error);
538 boolean prepareSolveStepByStep () raises (
Error);
544 boolean executeOneStep () raises (
Error);
548 void finishSolveStepByStep () raises (
Error);
566 out
unsigned long pathId, out
string report)
571 boolean reversePath (in
unsigned long pathId, out
unsigned long reversedPathId)
590 in
unsigned long pathId, in
boolean bothEdges)
594 void appendDirectPath (in
unsigned long pathId, in
floatSeq config, in
boolean validate)
598 void concatenatePath (in
unsigned long startId, in
unsigned long endId)
602 void extractPath (in
unsigned long pathId, in
double start, in
double end)
606 void erasePath (in
unsigned long pathId)
611 boolean projectPath (in
unsigned long patId) raises (
Error);
614 long numberPaths () raises (
Error);
621 intSeq optimizePath(in
unsigned long inPathId) raises (
Error);
626 double pathLength(in
unsigned long inPathId) raises (
Error);
632 floatSeq configAtParam(in
unsigned long inPathId, in
double atDistance)
640 floatSeq derivativeAtParam(in
unsigned long inPathId, in
unsigned long orderId, in
double atDistance)
656 void interruptPathPlanning() raises (
Error);
666 long numberNodes() raises (
Error);
672 long connectedComponentOfEdge(in
unsigned long edgeId) raises(
Error);
675 long connectedComponentOfNode(in
unsigned long nodeId) raises(
Error);
678 long numberEdges () raises (
Error);
685 long numberConnectedComponents ();
690 floatSeqSeq nodesConnectedComponent (in
unsigned long connectedComponentId)
699 floatSeq getNearestConfig(in
floatSeq config, in
long connectedComponentId, out
double distance)
703 void clearRoadmap () raises (
Error);
708 void resetRoadmap () raises (
Error);
712 void saveRoadmap (in
string filename) raises (
Error);
boost::posix_time::ptime point
RoadmapPtr_t readRoadmap(const std::string &filename, const ProblemPtr_t &problem)
Definition: robots.idl:28
Definition: path_planners.idl:21
Implement CORBA interface ``Obstacle''.
sequence< floatSeq > floatSeqSeq
Definition: common.idl:33
Definition: constraints.idl:40
Definition: distances.idl:19
Corba exception travelling through the Corba channel.
Definition: common.idl:24
Definition: path_validations.idl:22
sequence< string > Names_t
Sequence of names.
Definition: common.idl:22
sequence< long > intSeq
Definition: common.idl:29
virtual PathVectorPtr_t optimize(const PathVectorPtr_t &path)
sequence< boolean > boolSeq
Definition: common.idl:28
bool loadPlugin(const std::string &lib, ProblemSolver *ps)
double Quaternion_[4]
Definition: common.idl:40
Definition: steering_methods.idl:22
Definition: _problem.idl:28
double Transform_[7]
Element of SE(3) represented by a vector and a unit quaternion.
Definition: common.idl:36
To define and solve a path planning problem.
Definition: problem.idl:26
sequence< double > floatSeq
Robot configuration is defined by a sequence of dof value.
Definition: common.idl:32
sequence< intSeq > intSeqSeq
Definition: common.idl:30
FCL_REAL distance(const KDOP< N > &other, Vec3f *P=NULL, Vec3f *Q=NULL) const