hpp-corbaserver  4.9.0
Corba server for Humanoid Path Planner applications
problem.idl
Go to the documentation of this file.
1 // Copyright (C) 2009, 2010 by Florent Lamiraux, Thomas Moulard, JRL.
2 //
3 // This file is part of the hpp-corbaserver.
4 //
5 // This software is provided "as is" without warranty of any kind,
6 // either expressed or implied, including but not limited to the
7 // implied warranties of fitness for a particular purpose.
8 //
9 // See the COPYING file for more information.
10 
11 #ifndef HPP_CORBASERVER_PROBLEM_SERVER_IDL
12 #define HPP_CORBASERVER_PROBLEM_SERVER_IDL
13 #include <hpp/common.idl>
16 #include <hpp/core_idl/paths.idl>
21 
22 module hpp
23 {
24  module corbaserver {
26  interface Problem
27  {
29  void setRandomSeed (in long seed) raises (Error);
30 
32  void setMaxNumThreads (in unsigned short n) raises (Error);
33 
35  unsigned short getMaxNumThreads () raises (Error);
36 
40  Names_t getAvailable (in string type) raises (Error);
41 
46  Names_t getSelected (in string type) raises (Error);
47 
50  void setParameter (in string name, in any value) raises (Error);
51 
54  any getParameter (in string name) raises (Error);
55 
58  string getParameterDoc (in string name) raises (Error);
59 
64  boolean selectProblem (in string name) raises (Error);
65 
67  void resetProblem () raises (Error);
68 
70  boolean loadPlugin (in string pluginName) raises (Error);
71 
77  void movePathToProblem (in unsigned long pathId, in string problemName,
78  in Names_t jointNames) raises (Error);
79 
82 
86  void setInitialConfig (in floatSeq dofArray) raises (Error);
87 
90  floatSeq getInitialConfig () raises (Error);
91 
95  void addGoalConfig (in floatSeq dofArray) raises (Error);
96 
99  floatSeqSeq getGoalConfigs () raises (Error);
100 
102  void resetGoalConfigs () raises (Error);
103 
105 
108 
115  boolean applyConstraints (in floatSeq input, out floatSeq output,
116  out double residualError)
117  raises (Error);
118 
125  boolean optimize (in floatSeq input, out floatSeq output,
126  out floatSeq residualError)
127  raises (Error);
128 
139  void computeValueAndJacobian (in floatSeq config, out floatSeq value,
140  out floatSeqSeq jacobian) raises (Error);
141 
150  boolean generateValidConfig (in unsigned long maxIter, out floatSeq output,
151  out double residualError)
152  raises (Error);
153 
165  void createOrientationConstraint
166  (in string constraintName, in string joint1Name,
167  in string joint2Name, in Quaternion_ p,
168  in boolSeq mask) raises (Error);
169 
170 
181  void createTransformationConstraint
182  (in string constraintName, in string joint1Name,
183  in string joint2Name, in Transform_ ref,
184  in boolSeq mask) raises (Error);
185 
188  void createTransformationSE3Constraint
189  (in string constraintName, in string joint1Name, in string joint2Name,
190  in Transform_ frame1, in Transform_ frame2, in boolSeq mask) raises (Error);
191 
203  void createTransformationConstraint2
204  (in string constraintName, in string joint1Name,
205  in string joint2Name, in Transform_ frame1, in Transform_ frame2,
206  in boolSeq mask) raises (Error);
207 
212  void createLockedJoint (in string lockedJointName,
213  in string jointName,
214  in floatSeq value) raises (Error);
215 
222  void createLockedExtraDof (in string lockedDofName,
223  in unsigned long index,
224  in floatSeq value) raises (Error);
225 
229  void createManipulability (in string name,
230  in string function) raises (Error);
231 
246  void createComBeetweenFeet (in string constraintName, in string comName,
247  in string jointLName, in string jointRName, in floatSeq pointL,
248  in floatSeq pointR, in string jointRefName, in floatSeq pointRef,
249  in boolSeq mask)
250  raises (Error);
251 
261  void createRelativeComConstraint (in string constraintName, in string comName,
262  in string jointLName, in floatSeq point, in boolSeq mask)
263  raises (Error);
264 
265  void createConvexShapeContactConstraint
266  (in string constraintName, in Names_t floorJoints, in Names_t objectJoints,
267  in floatSeqSeq pts, in intSeqSeq objectTriangles,
268  in intSeqSeq floorTriangles) raises (Error);
269 
270  void createStaticStabilityConstraint (in string constraintName,
271  in Names_t jointNames, in floatSeqSeq points, in floatSeqSeq normals,
272  in string comRootJointName)
273  raises (Error);
274 
286  void createPositionConstraint (in string constraintName,
287  in string joint1Name,
288  in string joint2Name,
289  in floatSeq point1,
290  in floatSeq point2,
291  in boolSeq mask)
292  raises (Error);
293 
296  void createConfigurationConstraint (in string constraintName,
297  in floatSeq goal,
298  in floatSeq weights)
299  raises (Error);
300 
301 
309  void createDistanceBetweenJointConstraint
310  (in string constraintName, in string joint1Name, in string joint2Name,
311  in double distance) raises (Error);
312 
320  void createDistanceBetweenJointAndObjects
321  (in string constraintName, in string joint1Name, in Names_t objects,
322  in double distance) raises (Error);
323 
331  void createIdentityConstraint
332  (in string constraintName, in Names_t inJoints, in Names_t outJoints)
333  raises (Error);
334 
336  void resetConstraints () raises (Error);
337 
339  void resetConstraintMap () raises (Error);
340 
344  void addPassiveDofs (in string constraintName, in Names_t jointNames)
345  raises (Error);
346 
348  void getConstraintDimensions (in string constraintName,
349  out unsigned long inputSize , out unsigned long inputDerivativeSize,
350  out unsigned long outputSize, out unsigned long outputDerivativeSize)
351  raises (Error);
352 
359  void setConstantRightHandSide (in string constraintName,
360  in boolean constant)
361  raises (Error);
362 
366  boolean getConstantRightHandSide (in string constraintName)
367  raises (Error);
368 
370  floatSeq getRightHandSide () raises (Error);
371 
376  void setRightHandSide (in floatSeq rhs) raises (Error);
377 
383  void setRightHandSideFromConfig (in floatSeq config) raises (Error);
384 
389  void setRightHandSideByName (in string constraintName, in floatSeq rhs)
390  raises (Error);
391 
396  void setRightHandSideFromConfigByName (in string constraintName, in floatSeq config)
397  raises (Error);
398 
405  void addNumericalConstraints (in string configProjName,
406  in Names_t constraintNames,
407  in intSeq priorities)
408  raises (Error);
409 
413  void setNumericalConstraintsLastPriorityOptional (in boolean optional)
414  raises (Error);
415 
422  void addLockedJointConstraints (in string configProjName,
423  in Names_t lockedJointNames) raises (Error);
424 
426  string displayConstraints () raises (Error);
427 
429  double getErrorThreshold () raises (Error);
430 
432  void setErrorThreshold (in double threshold) raises (Error);
433 
434  void setDefaultLineSearchType (in string type) raises (Error);
435 
437  unsigned long getMaxIterProjection () raises (Error);
438 
440  void setMaxIterProjection (in unsigned long iterations) raises (Error);
441 
443  unsigned long getMaxIterPathPlanning () raises (Error);
444 
446  void setMaxIterPathPlanning (in unsigned long iterations) raises (Error);
447 
450 
452  void scCreateScalarMultiply (in string outName, in double scalar, in string inName) raises (Error);
453 
455  double getTimeOutPathPlanning () raises (Error);
456 
458  void setTimeOutPathPlanning (in double timeOut) raises (Error);
459 
460 
463 
466 
470  void filterCollisionPairs () raises (Error);
471 
473 
476 
481  void selectPathPlanner (in string pathPlannerType) raises (Error);
482 
487  void selectConfigurationShooter (in string configurationShooterType) raises (Error);
488 
493  void selectDistance (in string distanceType) raises (Error);
494 
495 
500  void selectSteeringMethod (in string steeringMethodType) raises (Error);
501 
505  void addPathOptimizer (in string pathOptimizerType) raises (Error);
506 
508  void clearPathOptimizers () raises (Error);
509 
514  void addConfigValidation (in string configValidationType) raises (Error);
515 
517  void clearConfigValidations () raises (Error);
518 
524  void selectPathValidation (in string pathValidationType,
525  in double tolerance) raises (Error);
526 
532  void selectPathProjector (in string pathProjectorType,
533  in double tolerance) raises (Error);
534 
538  boolean prepareSolveStepByStep () raises (Error);
539 
544  boolean executeOneStep () raises (Error);
545 
548  void finishSolveStepByStep () raises (Error);
549 
554  intSeq solve() raises (Error);
555 
564  boolean directPath (in floatSeq startConfig, in floatSeq endConfig,
565  in boolean validate,
566  out unsigned long pathId, out string report)
567  raises (Error);
568 
571  boolean reversePath (in unsigned long pathId, out unsigned long reversedPathId)
572  raises (Error);
573 
579  void addConfigToRoadmap (in floatSeq config) raises(Error);
580 
589  void addEdgeToRoadmap (in floatSeq config1, in floatSeq config2,
590  in unsigned long pathId, in boolean bothEdges)
591  raises (Error);
592 
594  void appendDirectPath (in unsigned long pathId, in floatSeq config, in boolean validate)
595  raises (Error);
596 
598  void concatenatePath (in unsigned long startId, in unsigned long endId)
599  raises (Error);
600 
602  void extractPath (in unsigned long pathId, in double start, in double end)
603  raises (Error);
604 
606  void erasePath (in unsigned long pathId)
607  raises (Error);
608 
611  boolean projectPath (in unsigned long patId) raises (Error);
612 
614  long numberPaths () raises (Error);
615 
621  intSeq optimizePath(in unsigned long inPathId) raises (Error);
622 
626  double pathLength(in unsigned long inPathId) raises (Error);
627 
632  floatSeq configAtParam(in unsigned long inPathId, in double atDistance)
633  raises (Error);
634 
640  floatSeq derivativeAtParam(in unsigned long inPathId, in unsigned long orderId, in double atDistance)
641  raises (Error);
642 
645  floatSeqSeq getWaypoints (in unsigned long pathId, out floatSeq times) raises (Error);
646 
648 
651 
656  void interruptPathPlanning() raises (Error);
658 
661 
663  floatSeqSeq nodes () raises (Error);
664 
665  // number of nodes in the roadmap
666  long numberNodes() raises (Error);
667 
668  // return the configuration of the node nodeId
669  floatSeq node(in unsigned long nodeId) raises(Error);
670 
672  long connectedComponentOfEdge(in unsigned long edgeId) raises(Error);
673 
675  long connectedComponentOfNode(in unsigned long nodeId) raises(Error);
676 
678  long numberEdges () raises (Error);
679 
681  void edge (in unsigned long edgeId, out floatSeq q1, out floatSeq q2)
682  raises (Error);
683 
685  long numberConnectedComponents ();
686 
690  floatSeqSeq nodesConnectedComponent (in unsigned long connectedComponentId)
691  raises (Error);
692 
699  floatSeq getNearestConfig(in floatSeq config, in long connectedComponentId, out double distance)
700  raises (Error);
701 
703  void clearRoadmap () raises (Error);
704 
708  void resetRoadmap () raises (Error);
709 
712  void saveRoadmap (in string filename) raises (Error);
713 
716  void readRoadmap (in string filename) raises (Error);
717 
718  core_idl::Distance getDistance () raises (Error);
719 
720  void setDistance (in core_idl::Distance distance) raises (Error);
721 
722  core_idl::Path getPath (in unsigned long pathId) raises (Error);
723 
724  unsigned long addPath (in core_idl::PathVector _path) raises (Error);
725 
726  core_idl::SteeringMethod getSteeringMethod () raises (Error);
727 
728  core_idl::PathValidation getPathValidation () raises (Error);
729 
730  core_idl::PathPlanner getPathPlanner () raises (Error);
731 
732  core_idl::Problem getProblem () raises (Error);
733 
734  constraints_idl::Implicit getConstraint (in string constraintName) raises (Error);
735 
736  void setRobot (in pinocchio_idl::Device robot) raises (Error);
738  };
739  }; // interface Problem
740 }; // module hpp
741 #endif
boost::posix_time::ptime point
void solve()
RoadmapPtr_t readRoadmap(const std::string &filename, const ProblemPtr_t &problem)
Vec3f n
Definition: robots.idl:28
Definition: path_planners.idl:21
Implement CORBA interface ``Obstacle&#39;&#39;.
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
Definition: paths.idl:21
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
Definition: paths.idl:64
sequence< intSeq > intSeqSeq
Definition: common.idl:30
Vec3f * points
FCL_REAL distance(const KDOP< N > &other, Vec3f *P=NULL, Vec3f *Q=NULL) const