hpp-corbaserver  4.10.1
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 
221  void createLockedJointWithComp (in string lockedJointName,
222  in string jointName,
223  in floatSeq value,
224  in ComparisonTypes_t comp) raises (Error);
225 
232  void createLockedExtraDof (in string lockedDofName,
233  in unsigned long index,
234  in floatSeq value) raises (Error);
235 
239  void createManipulability (in string name,
240  in string function) raises (Error);
241 
256  void createComBeetweenFeet (in string constraintName, in string comName,
257  in string jointLName, in string jointRName, in floatSeq pointL,
258  in floatSeq pointR, in string jointRefName, in floatSeq pointRef,
259  in boolSeq mask)
260  raises (Error);
261 
271  void createRelativeComConstraint (in string constraintName, in string comName,
272  in string jointLName, in floatSeq point, in boolSeq mask)
273  raises (Error);
274 
275  void createConvexShapeContactConstraint
276  (in string constraintName, in Names_t floorJoints, in Names_t objectJoints,
277  in floatSeqSeq pts, in intSeqSeq objectTriangles,
278  in intSeqSeq floorTriangles) raises (Error);
279 
280  void createStaticStabilityConstraint (in string constraintName,
281  in Names_t jointNames, in floatSeqSeq points, in floatSeqSeq normals,
282  in string comRootJointName)
283  raises (Error);
284 
296  void createPositionConstraint (in string constraintName,
297  in string joint1Name,
298  in string joint2Name,
299  in floatSeq point1,
300  in floatSeq point2,
301  in boolSeq mask)
302  raises (Error);
303 
306  void createConfigurationConstraint (in string constraintName,
307  in floatSeq goal,
308  in floatSeq weights)
309  raises (Error);
310 
311 
319  void createDistanceBetweenJointConstraint
320  (in string constraintName, in string joint1Name, in string joint2Name,
321  in double distance) raises (Error);
322 
330  void createDistanceBetweenJointAndObjects
331  (in string constraintName, in string joint1Name, in Names_t objects,
332  in double distance) raises (Error);
333 
341  void createIdentityConstraint
342  (in string constraintName, in Names_t inJoints, in Names_t outJoints)
343  raises (Error);
344 
346  void resetConstraints () raises (Error);
347 
349  void resetConstraintMap () raises (Error);
350 
354  void addPassiveDofs (in string constraintName, in Names_t jointNames)
355  raises (Error);
356 
358  void getConstraintDimensions (in string constraintName,
359  out unsigned long inputSize , out unsigned long inputDerivativeSize,
360  out unsigned long outputSize, out unsigned long outputDerivativeSize)
361  raises (Error);
362 
369  void setConstantRightHandSide (in string constraintName,
370  in boolean constant)
371  raises (Error);
372 
376  boolean getConstantRightHandSide (in string constraintName)
377  raises (Error);
378 
380  floatSeq getRightHandSide () raises (Error);
381 
386  void setRightHandSide (in floatSeq rhs) raises (Error);
387 
393  void setRightHandSideFromConfig (in floatSeq config) raises (Error);
394 
399  void setRightHandSideByName (in string constraintName, in floatSeq rhs)
400  raises (Error);
401 
406  void setRightHandSideFromConfigByName (in string constraintName, in floatSeq config)
407  raises (Error);
408 
415  void addNumericalConstraints (in string configProjName,
416  in Names_t constraintNames,
417  in intSeq priorities)
418  raises (Error);
419 
423  void setNumericalConstraintsLastPriorityOptional (in boolean optional)
424  raises (Error);
425 
432  void addLockedJointConstraints (in string configProjName,
433  in Names_t lockedJointNames) raises (Error);
434 
436  string displayConstraints () raises (Error);
437 
439  double getErrorThreshold () raises (Error);
440 
442  void setErrorThreshold (in double threshold) raises (Error);
443 
444  void setDefaultLineSearchType (in string type) raises (Error);
445 
447  unsigned long getMaxIterProjection () raises (Error);
448 
450  void setMaxIterProjection (in unsigned long iterations) raises (Error);
451 
453  unsigned long getMaxIterPathPlanning () raises (Error);
454 
456  void setMaxIterPathPlanning (in unsigned long iterations) raises (Error);
457 
460 
462  void scCreateScalarMultiply (in string outName, in double scalar, in string inName) raises (Error);
463 
465  double getTimeOutPathPlanning () raises (Error);
466 
468  void setTimeOutPathPlanning (in double timeOut) raises (Error);
469 
470 
473 
476 
480  void filterCollisionPairs () raises (Error);
481 
483 
486 
491  void selectPathPlanner (in string pathPlannerType) raises (Error);
492 
497  void selectConfigurationShooter (in string configurationShooterType) raises (Error);
498 
503  void selectDistance (in string distanceType) raises (Error);
504 
505 
510  void selectSteeringMethod (in string steeringMethodType) raises (Error);
511 
515  void addPathOptimizer (in string pathOptimizerType) raises (Error);
516 
518  void clearPathOptimizers () raises (Error);
519 
524  void addConfigValidation (in string configValidationType) raises (Error);
525 
527  void clearConfigValidations () raises (Error);
528 
534  void selectPathValidation (in string pathValidationType,
535  in double tolerance) raises (Error);
536 
542  void selectPathProjector (in string pathProjectorType,
543  in double tolerance) raises (Error);
544 
548  boolean prepareSolveStepByStep () raises (Error);
549 
554  boolean executeOneStep () raises (Error);
555 
558  void finishSolveStepByStep () raises (Error);
559 
564  intSeq solve() raises (Error);
565 
574  boolean directPath (in floatSeq startConfig, in floatSeq endConfig,
575  in boolean validate,
576  out unsigned long pathId, out string report)
577  raises (Error);
578 
581  boolean reversePath (in unsigned long pathId, out unsigned long reversedPathId)
582  raises (Error);
583 
589  void addConfigToRoadmap (in floatSeq config) raises(Error);
590 
599  void addEdgeToRoadmap (in floatSeq config1, in floatSeq config2,
600  in unsigned long pathId, in boolean bothEdges)
601  raises (Error);
602 
604  void appendDirectPath (in unsigned long pathId, in floatSeq config, in boolean validate)
605  raises (Error);
606 
608  void concatenatePath (in unsigned long startId, in unsigned long endId)
609  raises (Error);
610 
612  void extractPath (in unsigned long pathId, in double start, in double end)
613  raises (Error);
614 
616  void erasePath (in unsigned long pathId)
617  raises (Error);
618 
621  boolean projectPath (in unsigned long patId) raises (Error);
622 
624  long numberPaths () raises (Error);
625 
631  intSeq optimizePath(in unsigned long inPathId) raises (Error);
632 
636  double pathLength(in unsigned long inPathId) raises (Error);
637 
642  floatSeq configAtParam(in unsigned long inPathId, in double atDistance)
643  raises (Error);
644 
650  floatSeq derivativeAtParam(in unsigned long inPathId, in unsigned long orderId, in double atDistance)
651  raises (Error);
652 
655  floatSeqSeq getWaypoints (in unsigned long pathId, out floatSeq times) raises (Error);
656 
658 
661 
666  void interruptPathPlanning() raises (Error);
668 
671 
673  floatSeqSeq nodes () raises (Error);
674 
675  // number of nodes in the roadmap
676  long numberNodes() raises (Error);
677 
678  // return the configuration of the node nodeId
679  floatSeq node(in unsigned long nodeId) raises(Error);
680 
682  long connectedComponentOfEdge(in unsigned long edgeId) raises(Error);
683 
685  long connectedComponentOfNode(in unsigned long nodeId) raises(Error);
686 
688  long numberEdges () raises (Error);
689 
691  void edge (in unsigned long edgeId, out floatSeq q1, out floatSeq q2)
692  raises (Error);
693 
695  long numberConnectedComponents ();
696 
700  floatSeqSeq nodesConnectedComponent (in unsigned long connectedComponentId)
701  raises (Error);
702 
709  floatSeq getNearestConfig(in floatSeq config, in long connectedComponentId, out double distance)
710  raises (Error);
711 
713  void clearRoadmap () raises (Error);
714 
718  void resetRoadmap () raises (Error);
719 
722  void saveRoadmap (in string filename) raises (Error);
723 
726  void readRoadmap (in string filename) raises (Error);
727 
728  core_idl::Distance getDistance () raises (Error);
729 
730  void setDistance (in core_idl::Distance distance) raises (Error);
731 
732  core_idl::Path getPath (in unsigned long pathId) raises (Error);
733 
734  unsigned long addPath (in core_idl::PathVector _path) raises (Error);
735 
736  core_idl::SteeringMethod getSteeringMethod () raises (Error);
737 
738  core_idl::PathValidation getPathValidation () raises (Error);
739 
740  core_idl::PathPlanner getPathPlanner () raises (Error);
741 
742  core_idl::Problem getProblem () raises (Error);
743 
744  constraints_idl::Implicit getConstraint (in string constraintName) raises (Error);
745 
746  void setRobot (in pinocchio_idl::Device robot) raises (Error);
748  };
749  }; // interface Problem
750 }; // module hpp
751 #endif
Definition: robots.idl:28
Definition: path_planners.idl:67
Definition: common-idl.hh:342
Implement CORBA interface ``Obstacle&#39;&#39;.
Definition: basic-server.hh:27
Definition: constraints.idl:40
Definition: distances.idl:19
Corba exception travelling through the Corba channel.
Definition: common.idl:24
Definition: path_validations.idl:22
::CORBA::Double Transform_[7]
Definition: common-idl.hh:796
::CORBA::Double Quaternion_[4]
Definition: common-idl.hh:958
Definition: common-idl.hh:73
Definition: common-idl.hh:684
Definition: common-idl.hh:228
Definition: steering_methods.idl:22
Definition: common-idl.hh:1019
Definition: common-idl.hh:456
Definition: _problem.idl:28
Definition: paths.idl:22
To define and solve a path planning problem.
Definition: problem.idl:26
Definition: common-idl.hh:570
Definition: paths.idl:67