hpp-corbaserver  6.0.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>
22 
23 module hpp
24 {
25  module corbaserver {
27  interface Problem
28  {
30  void setRandomSeed (in long seed) raises (Error);
31 
33  void setMaxNumThreads (in unsigned short n) raises (Error);
34 
36  unsigned short getMaxNumThreads () raises (Error);
37 
41  Names_t getAvailable (in string type) raises (Error);
42 
47  Names_t getSelected (in string type) raises (Error);
48 
51  void setParameter (in string name, in any value) raises (Error);
52 
55  any getParameter (in string name) raises (Error);
56 
59  string getParameterDoc (in string name) raises (Error);
60 
65  boolean selectProblem (in string name) raises (Error);
66 
68  void resetProblem () raises (Error);
69 
71  boolean loadPlugin (in string pluginName) raises (Error);
72 
78  void movePathToProblem (in unsigned long pathId, in string problemName,
79  in Names_t jointNames) raises (Error);
80 
83 
87  void setInitialConfig (in floatSeq dofArray) raises (Error);
88 
91  floatSeq getInitialConfig () raises (Error);
92 
96  void addGoalConfig (in floatSeq dofArray) raises (Error);
97 
100  floatSeqSeq getGoalConfigs () raises (Error);
101 
103  void resetGoalConfigs () raises (Error);
104 
106  void setGoalConstraints(in Names_t constraints) raises(Error);
107 
109  void resetGoalConstraints() raises(Error);
110 
112 
115 
122  boolean applyConstraints (in floatSeq input, out floatSeq output,
123  out double residualError)
124  raises (Error);
125 
132  boolean optimize (in floatSeq input, out floatSeq output,
133  out floatSeq residualError)
134  raises (Error);
135 
146  void computeValueAndJacobian (in floatSeq config, out floatSeq value,
147  out floatSeqSeq jacobian) raises (Error);
148 
157  boolean generateValidConfig (in unsigned long maxIter, out floatSeq output,
158  out double residualError)
159  raises (Error);
160 
172  void createOrientationConstraint
173  (in string constraintName, in string joint1Name,
174  in string joint2Name, in Quaternion_ p,
175  in boolSeq mask) raises (Error);
176 
177 
188  void createTransformationConstraint
189  (in string constraintName, in string joint1Name,
190  in string joint2Name, in Transform_ ref,
191  in boolSeq mask) raises (Error);
192 
195  void createTransformationR3xSO3Constraint
196  (in string constraintName, in string joint1Name, in string joint2Name,
197  in Transform_ frame1, in Transform_ frame2, in boolSeq mask) raises (Error);
198 
210  void createTransformationConstraint2
211  (in string constraintName, in string joint1Name,
212  in string joint2Name, in Transform_ frame1, in Transform_ frame2,
213  in boolSeq mask) raises (Error);
214 
219  void createLockedJoint (in string lockedJointName,
220  in string jointName,
221  in floatSeq value) raises (Error);
222 
228  void createLockedJointWithComp (in string lockedJointName,
229  in string jointName,
230  in floatSeq value,
231  in ComparisonTypes_t comp) raises (Error);
232 
239  void createLockedExtraDof (in string lockedDofName,
240  in unsigned long index,
241  in floatSeq value) raises (Error);
242 
246  void createManipulability (in string name,
247  in string function) raises (Error);
248 
263  void createComBeetweenFeet (in string constraintName, in string comName,
264  in string jointLName, in string jointRName, in floatSeq pointL,
265  in floatSeq pointR, in string jointRefName, in floatSeq pointRef,
266  in boolSeq mask)
267  raises (Error);
268 
278  void createRelativeComConstraint (in string constraintName, in string comName,
279  in string jointLName, in floatSeq point, in boolSeq mask)
280  raises (Error);
281 
282  void createConvexShapeContactConstraint
283  (in string constraintName, in Names_t floorJoints, in Names_t objectJoints,
284  in floatSeqSeq pts, in intSeqSeq objectTriangles,
285  in intSeqSeq floorTriangles) raises (Error);
286 
298  void createPositionConstraint (in string constraintName,
299  in string joint1Name,
300  in string joint2Name,
301  in floatSeq point1,
302  in floatSeq point2,
303  in boolSeq mask)
304  raises (Error);
305 
308  void createConfigurationConstraint (in string constraintName,
309  in floatSeq goal,
310  in floatSeq weights)
311  raises (Error);
312 
313 
321  void createDistanceBetweenJointConstraint
322  (in string constraintName, in string joint1Name, in string joint2Name,
323  in double distance) raises (Error);
324 
332  void createDistanceBetweenJointAndObjects
333  (in string constraintName, in string joint1Name, in Names_t objects,
334  in double distance) raises (Error);
335 
343  void createIdentityConstraint
344  (in string constraintName, in Names_t inJoints, in Names_t outJoints)
345  raises (Error);
346 
348  void resetConstraints () raises (Error);
349 
351  void resetConstraintMap () raises (Error);
352 
356  void addPassiveDofs (in string constraintName, in Names_t jointNames)
357  raises (Error);
358 
360  void getConstraintDimensions (in string constraintName,
361  out unsigned long inputSize , out unsigned long inputDerivativeSize,
362  out unsigned long outputSize, out unsigned long outputDerivativeSize)
363  raises (Error);
364 
371  void setConstantRightHandSide (in string constraintName,
372  in boolean constant)
373  raises (Error);
374 
378  boolean getConstantRightHandSide (in string constraintName)
379  raises (Error);
380 
382  floatSeq getRightHandSide () raises (Error);
383 
388  void setRightHandSide (in floatSeq rhs) raises (Error);
389 
395  void setRightHandSideFromConfig (in floatSeq config) raises (Error);
396 
401  void setRightHandSideByName (in string constraintName, in floatSeq rhs)
402  raises (Error);
403 
408  void setRightHandSideFromConfigByName (in string constraintName, in floatSeq config)
409  raises (Error);
410 
417  void addNumericalConstraints (in string configProjName,
418  in Names_t constraintNames,
419  in intSeq priorities)
420  raises (Error);
421 
425  void setNumericalConstraintsLastPriorityOptional (in boolean optional)
426  raises (Error);
427 
434  void addLockedJointConstraints (in string configProjName,
435  in Names_t lockedJointNames) raises (Error);
436 
438  string displayConstraints () raises (Error);
439 
441  double getErrorThreshold () raises (Error);
442 
444  void setErrorThreshold (in double threshold) raises (Error);
445 
446  void setDefaultLineSearchType (in string type) raises (Error);
447 
449  unsigned long getMaxIterProjection () raises (Error);
450 
452  void setMaxIterProjection (in unsigned long iterations) raises (Error);
453 
455  unsigned long getMaxIterPathPlanning () raises (Error);
456 
458  void setMaxIterPathPlanning (in unsigned long iterations) raises (Error);
459 
462 
464  void scCreateScalarMultiply (in string outName, in double scalar, in string inName) raises (Error);
465 
467  double getTimeOutPathPlanning () raises (Error);
468 
470  void setTimeOutPathPlanning (in double timeOut) raises (Error);
471 
472 
475 
478 
482  void filterCollisionPairs () raises (Error);
483 
485 
488 
493  void selectPathPlanner (in string pathPlannerType) raises (Error);
494 
499  void selectConfigurationShooter (in string configurationShooterType) raises (Error);
500 
505  void selectDistance (in string distanceType) raises (Error);
506 
507 
512  void selectSteeringMethod (in string steeringMethodType) raises (Error);
513 
517  void addPathOptimizer (in string pathOptimizerType) raises (Error);
518 
520  void clearPathOptimizers () raises (Error);
521 
526  void addConfigValidation (in string configValidationType) raises (Error);
527 
529  void clearConfigValidations () raises (Error);
530 
536  void selectPathValidation (in string pathValidationType,
537  in double tolerance) raises (Error);
538 
544  void selectPathProjector (in string pathProjectorType,
545  in double tolerance) raises (Error);
546 
550  boolean prepareSolveStepByStep () raises (Error);
551 
556  boolean executeOneStep () raises (Error);
557 
560  void finishSolveStepByStep () raises (Error);
561 
566  intSeq solve() raises (Error);
567 
576  boolean directPath (in floatSeq startConfig, in floatSeq endConfig,
577  in boolean validate,
578  out unsigned long pathId, out string report)
579  raises (Error);
580 
583  boolean reversePath (in unsigned long pathId, out unsigned long reversedPathId)
584  raises (Error);
585 
591  void addConfigToRoadmap (in floatSeq config) raises(Error);
592 
601  void addEdgeToRoadmap (in floatSeq config1, in floatSeq config2,
602  in unsigned long pathId, in boolean bothEdges)
603  raises (Error);
604 
606  void appendDirectPath (in unsigned long pathId, in floatSeq config, in boolean validate)
607  raises (Error);
608 
610  void concatenatePath (in unsigned long startId, in unsigned long endId)
611  raises (Error);
612 
614  void extractPath (in unsigned long pathId, in double start, in double end)
615  raises (Error);
616 
618  void erasePath (in unsigned long pathId)
619  raises (Error);
620 
623  boolean projectPath (in unsigned long patId) raises (Error);
624 
626  long numberPaths () raises (Error);
627 
633  intSeq optimizePath(in unsigned long inPathId) raises (Error);
634 
638  double pathLength(in unsigned long inPathId) raises (Error);
639 
644  floatSeq configAtParam(in unsigned long inPathId, in double atDistance)
645  raises (Error);
646 
652  floatSeq derivativeAtParam(in unsigned long inPathId, in unsigned long orderId, in double atDistance)
653  raises (Error);
654 
657  floatSeqSeq getWaypoints (in unsigned long pathId, out floatSeq times) raises (Error);
658 
660 
663 
668  void interruptPathPlanning() raises (Error);
670 
673 
675  floatSeqSeq nodes () raises (Error);
676 
677  // number of nodes in the roadmap
678  long numberNodes() raises (Error);
679 
680  // return the configuration of the node nodeId
681  floatSeq node(in unsigned long nodeId) raises(Error);
682 
684  long connectedComponentOfEdge(in unsigned long edgeId) raises(Error);
685 
687  long connectedComponentOfNode(in unsigned long nodeId) raises(Error);
688 
690  long numberEdges () raises (Error);
691 
693  void edge (in unsigned long edgeId, out floatSeq q1, out floatSeq q2)
694  raises (Error);
695 
697  long numberConnectedComponents ();
698 
702  floatSeqSeq nodesConnectedComponent (in unsigned long connectedComponentId)
703  raises (Error);
704 
711  floatSeq getNearestConfig(in floatSeq config, in long connectedComponentId, out double distance)
712  raises (Error);
713 
715  void clearRoadmap () raises (Error);
716 
720  void resetRoadmap () raises (Error);
721 
725  void saveRoadmap (in string filename) raises (Error);
726 
731  void loadRoadmap (in string filename) raises (Error);
733 
734  core_idl::Distance getDistance () raises (Error);
735 
736  void setDistance (in core_idl::Distance distance) raises (Error);
737 
738  core_idl::Path getPath (in unsigned long pathId) raises (Error);
739 
740  unsigned long addPath (in core_idl::PathVector _path) raises (Error);
741 
746  void savePath (in core_idl::Path _path, in string filename) raises (Error);
747 
751  core_idl::Path loadPath (in string filename) raises (Error);
752 
753  core_idl::SteeringMethod getSteeringMethod () raises (Error);
754 
755  core_idl::PathValidation getPathValidation () raises (Error);
756 
757  core_idl::PathPlanner getPathPlanner () raises (Error);
758 
759  core_idl::Problem getProblem () raises (Error);
760 
761  constraints_idl::Implicit getConstraint (in string constraintName) raises (Error);
762 
763  void setRobot (in pinocchio_idl::Device robot) raises (Error);
764 
765  pinocchio_idl::CollisionObject getObstacle(in string name) raises (Error);
766 
769  core_idl::Problem createProblem (in pinocchio_idl::Device robot) raises (Error);
770 
771  core_idl::Roadmap createRoadmap(in core_idl::Distance distance, in pinocchio_idl::Device robot) raises (Error);
772 
780  core_idl::Roadmap readRoadmap(in string filename,
781  in pinocchio_idl::Device robot)
782  raises (Error);
790  void writeRoadmap(in string filename,
791  in core_idl::Roadmap roadmap,
792  in pinocchio_idl::Device robot)
793  raises (Error);
794 
795  core_idl::PathPlanner createPathPlanner (in string type, in core_idl::Problem _problem, in core_idl::Roadmap roadmap) raises (Error);
796  core_idl::PathOptimizer createPathOptimizer (in string type, in core_idl::Problem _problem) raises (Error);
797 
798  core_idl::ConfigValidation createConfigValidation (in string type, in pinocchio_idl::Device robot) raises (Error);
799  core_idl::PathValidation createPathValidation (in string type, in pinocchio_idl::Device robot, in value_type parameter) raises (Error);
800  core_idl::PathProjector createPathProjector (in string type, in core_idl::Problem robot, in value_type parameter) raises (Error);
801  core_idl::ConfigurationShooter createConfigurationShooter (in string type, in core_idl::Problem _problem) raises (Error);
802  core_idl::Distance createDistance (in string type, in core_idl::Problem _problem) raises (Error);
803  core_idl::SteeringMethod createSteeringMethod (in string type, in core_idl::Problem _problem) raises (Error);
804 
805  core_idl::Constraint createConstraintSet (in pinocchio_idl::Device robot, in string name) raises (Error);
806  core_idl::Constraint createConfigProjector (in pinocchio_idl::Device robot, in string name, in double threshold, in unsigned long iterations) raises (Error);
807 
809  };
810  }; // interface Problem
811 }; // module hpp
812 #endif
Definition: robots-idl.hh:388
Definition: common-idl.hh:1138
Definition: path_validations-idl.hh:118
Definition: configuration_shooters-idl.hh:94
Definition: _constraints-idl.hh:242
Definition: robots-idl.hh:221
Definition: distances-idl.hh:94
Definition: constraints-idl.hh:223
Definition: common-idl.hh:78
Definition: path_planners-idl.hh:647
Definition: path_planners-idl.hh:506
Definition: path_projectors-idl.hh:106
Definition: path_validations-idl.hh:481
Definition: paths-idl.hh:302
Definition: paths-idl.hh:157
Definition: path_planners-idl.hh:365
Definition: steering_methods-idl.hh:106
Definition: common-idl.hh:347
Definition: common-idl.hh:803
Definition: common-idl.hh:689
Definition: common-idl.hh:575
Definition: common-idl.hh:461
::CORBA::Double Quaternion_[4]
Definition: common-idl.hh:1077
::CORBA::Double Transform_[7]
Definition: common-idl.hh:915
Corba exception travelling through the Corba channel.
Definition: common.idl:27
To define and solve a path planning problem.
Definition: problem.idl:28
void setRandomSeed(in long seed)
Set random seed of random number generator.
void setMaxNumThreads(in unsigned short n)
unsigned short getMaxNumThreads()
Implement CORBA interface `‘Obstacle’'.
Definition: client.hh:46
double value_type
Definition: common.idl:18