hpp-corbaserver  4.13.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  void setGoalConstraints(in Names_t constraints) raises(Error);
106 
108  void resetGoalConstraints() raises(Error);
109 
111 
114 
121  boolean applyConstraints (in floatSeq input, out floatSeq output,
122  out double residualError)
123  raises (Error);
124 
131  boolean optimize (in floatSeq input, out floatSeq output,
132  out floatSeq residualError)
133  raises (Error);
134 
145  void computeValueAndJacobian (in floatSeq config, out floatSeq value,
146  out floatSeqSeq jacobian) raises (Error);
147 
156  boolean generateValidConfig (in unsigned long maxIter, out floatSeq output,
157  out double residualError)
158  raises (Error);
159 
171  void createOrientationConstraint
172  (in string constraintName, in string joint1Name,
173  in string joint2Name, in Quaternion_ p,
174  in boolSeq mask) raises (Error);
175 
176 
187  void createTransformationConstraint
188  (in string constraintName, in string joint1Name,
189  in string joint2Name, in Transform_ ref,
190  in boolSeq mask) raises (Error);
191 
194  void createTransformationR3xSO3Constraint
195  (in string constraintName, in string joint1Name, in string joint2Name,
196  in Transform_ frame1, in Transform_ frame2, in boolSeq mask) raises (Error);
197 
209  void createTransformationConstraint2
210  (in string constraintName, in string joint1Name,
211  in string joint2Name, in Transform_ frame1, in Transform_ frame2,
212  in boolSeq mask) raises (Error);
213 
218  void createLockedJoint (in string lockedJointName,
219  in string jointName,
220  in floatSeq value) raises (Error);
221 
227  void createLockedJointWithComp (in string lockedJointName,
228  in string jointName,
229  in floatSeq value,
230  in ComparisonTypes_t comp) raises (Error);
231 
238  void createLockedExtraDof (in string lockedDofName,
239  in unsigned long index,
240  in floatSeq value) raises (Error);
241 
245  void createManipulability (in string name,
246  in string function) raises (Error);
247 
262  void createComBeetweenFeet (in string constraintName, in string comName,
263  in string jointLName, in string jointRName, in floatSeq pointL,
264  in floatSeq pointR, in string jointRefName, in floatSeq pointRef,
265  in boolSeq mask)
266  raises (Error);
267 
277  void createRelativeComConstraint (in string constraintName, in string comName,
278  in string jointLName, in floatSeq point, in boolSeq mask)
279  raises (Error);
280 
281  void createConvexShapeContactConstraint
282  (in string constraintName, in Names_t floorJoints, in Names_t objectJoints,
283  in floatSeqSeq pts, in intSeqSeq objectTriangles,
284  in intSeqSeq floorTriangles) raises (Error);
285 
297  void createPositionConstraint (in string constraintName,
298  in string joint1Name,
299  in string joint2Name,
300  in floatSeq point1,
301  in floatSeq point2,
302  in boolSeq mask)
303  raises (Error);
304 
307  void createConfigurationConstraint (in string constraintName,
308  in floatSeq goal,
309  in floatSeq weights)
310  raises (Error);
311 
312 
320  void createDistanceBetweenJointConstraint
321  (in string constraintName, in string joint1Name, in string joint2Name,
322  in double distance) raises (Error);
323 
331  void createDistanceBetweenJointAndObjects
332  (in string constraintName, in string joint1Name, in Names_t objects,
333  in double distance) raises (Error);
334 
342  void createIdentityConstraint
343  (in string constraintName, in Names_t inJoints, in Names_t outJoints)
344  raises (Error);
345 
347  void resetConstraints () raises (Error);
348 
350  void resetConstraintMap () raises (Error);
351 
355  void addPassiveDofs (in string constraintName, in Names_t jointNames)
356  raises (Error);
357 
359  void getConstraintDimensions (in string constraintName,
360  out unsigned long inputSize , out unsigned long inputDerivativeSize,
361  out unsigned long outputSize, out unsigned long outputDerivativeSize)
362  raises (Error);
363 
370  void setConstantRightHandSide (in string constraintName,
371  in boolean constant)
372  raises (Error);
373 
377  boolean getConstantRightHandSide (in string constraintName)
378  raises (Error);
379 
381  floatSeq getRightHandSide () raises (Error);
382 
387  void setRightHandSide (in floatSeq rhs) raises (Error);
388 
394  void setRightHandSideFromConfig (in floatSeq config) raises (Error);
395 
400  void setRightHandSideByName (in string constraintName, in floatSeq rhs)
401  raises (Error);
402 
407  void setRightHandSideFromConfigByName (in string constraintName, in floatSeq config)
408  raises (Error);
409 
416  void addNumericalConstraints (in string configProjName,
417  in Names_t constraintNames,
418  in intSeq priorities)
419  raises (Error);
420 
424  void setNumericalConstraintsLastPriorityOptional (in boolean optional)
425  raises (Error);
426 
433  void addLockedJointConstraints (in string configProjName,
434  in Names_t lockedJointNames) raises (Error);
435 
437  string displayConstraints () raises (Error);
438 
440  double getErrorThreshold () raises (Error);
441 
443  void setErrorThreshold (in double threshold) raises (Error);
444 
445  void setDefaultLineSearchType (in string type) raises (Error);
446 
448  unsigned long getMaxIterProjection () raises (Error);
449 
451  void setMaxIterProjection (in unsigned long iterations) raises (Error);
452 
454  unsigned long getMaxIterPathPlanning () raises (Error);
455 
457  void setMaxIterPathPlanning (in unsigned long iterations) raises (Error);
458 
461 
463  void scCreateScalarMultiply (in string outName, in double scalar, in string inName) raises (Error);
464 
466  double getTimeOutPathPlanning () raises (Error);
467 
469  void setTimeOutPathPlanning (in double timeOut) raises (Error);
470 
471 
474 
477 
481  void filterCollisionPairs () raises (Error);
482 
484 
487 
492  void selectPathPlanner (in string pathPlannerType) raises (Error);
493 
498  void selectConfigurationShooter (in string configurationShooterType) raises (Error);
499 
504  void selectDistance (in string distanceType) raises (Error);
505 
506 
511  void selectSteeringMethod (in string steeringMethodType) raises (Error);
512 
516  void addPathOptimizer (in string pathOptimizerType) raises (Error);
517 
519  void clearPathOptimizers () raises (Error);
520 
525  void addConfigValidation (in string configValidationType) raises (Error);
526 
528  void clearConfigValidations () raises (Error);
529 
535  void selectPathValidation (in string pathValidationType,
536  in double tolerance) raises (Error);
537 
543  void selectPathProjector (in string pathProjectorType,
544  in double tolerance) raises (Error);
545 
549  boolean prepareSolveStepByStep () raises (Error);
550 
555  boolean executeOneStep () raises (Error);
556 
559  void finishSolveStepByStep () raises (Error);
560 
565  intSeq solve() raises (Error);
566 
575  boolean directPath (in floatSeq startConfig, in floatSeq endConfig,
576  in boolean validate,
577  out unsigned long pathId, out string report)
578  raises (Error);
579 
582  boolean reversePath (in unsigned long pathId, out unsigned long reversedPathId)
583  raises (Error);
584 
590  void addConfigToRoadmap (in floatSeq config) raises(Error);
591 
600  void addEdgeToRoadmap (in floatSeq config1, in floatSeq config2,
601  in unsigned long pathId, in boolean bothEdges)
602  raises (Error);
603 
605  void appendDirectPath (in unsigned long pathId, in floatSeq config, in boolean validate)
606  raises (Error);
607 
609  void concatenatePath (in unsigned long startId, in unsigned long endId)
610  raises (Error);
611 
613  void extractPath (in unsigned long pathId, in double start, in double end)
614  raises (Error);
615 
617  void erasePath (in unsigned long pathId)
618  raises (Error);
619 
622  boolean projectPath (in unsigned long patId) raises (Error);
623 
625  long numberPaths () raises (Error);
626 
632  intSeq optimizePath(in unsigned long inPathId) raises (Error);
633 
637  double pathLength(in unsigned long inPathId) raises (Error);
638 
643  floatSeq configAtParam(in unsigned long inPathId, in double atDistance)
644  raises (Error);
645 
651  floatSeq derivativeAtParam(in unsigned long inPathId, in unsigned long orderId, in double atDistance)
652  raises (Error);
653 
656  floatSeqSeq getWaypoints (in unsigned long pathId, out floatSeq times) raises (Error);
657 
659 
662 
667  void interruptPathPlanning() raises (Error);
669 
672 
674  floatSeqSeq nodes () raises (Error);
675 
676  // number of nodes in the roadmap
677  long numberNodes() raises (Error);
678 
679  // return the configuration of the node nodeId
680  floatSeq node(in unsigned long nodeId) raises(Error);
681 
683  long connectedComponentOfEdge(in unsigned long edgeId) raises(Error);
684 
686  long connectedComponentOfNode(in unsigned long nodeId) raises(Error);
687 
689  long numberEdges () raises (Error);
690 
692  void edge (in unsigned long edgeId, out floatSeq q1, out floatSeq q2)
693  raises (Error);
694 
696  long numberConnectedComponents ();
697 
701  floatSeqSeq nodesConnectedComponent (in unsigned long connectedComponentId)
702  raises (Error);
703 
710  floatSeq getNearestConfig(in floatSeq config, in long connectedComponentId, out double distance)
711  raises (Error);
712 
714  void clearRoadmap () raises (Error);
715 
719  void resetRoadmap () raises (Error);
720 
724  void saveRoadmap (in string filename) raises (Error);
725 
730  void loadRoadmap (in string filename) raises (Error);
732 
733  core_idl::Distance getDistance () raises (Error);
734 
735  void setDistance (in core_idl::Distance distance) raises (Error);
736 
737  core_idl::Path getPath (in unsigned long pathId) raises (Error);
738 
739  unsigned long addPath (in core_idl::PathVector _path) raises (Error);
740 
741  core_idl::SteeringMethod getSteeringMethod () raises (Error);
742 
743  core_idl::PathValidation getPathValidation () raises (Error);
744 
745  core_idl::PathPlanner getPathPlanner () raises (Error);
746 
747  core_idl::Problem getProblem () raises (Error);
748 
749  constraints_idl::Implicit getConstraint (in string constraintName) raises (Error);
750 
751  void setRobot (in pinocchio_idl::Device robot) raises (Error);
752 
753  pinocchio_idl::CollisionObject getObstacle(in string name) raises (Error);
754 
757  core_idl::Problem createProblem (in pinocchio_idl::Device robot) raises (Error);
758 
759  core_idl::Roadmap createRoadmap(in core_idl::Distance distance, in pinocchio_idl::Device robot) raises (Error);
760 
768  core_idl::Roadmap readRoadmap(in string filename,
769  in pinocchio_idl::Device robot)
770  raises (Error);
778  void writeRoadmap(in string filename,
779  in core_idl::Roadmap roadmap,
780  in pinocchio_idl::Device robot)
781  raises (Error);
782 
783  core_idl::PathPlanner createPathPlanner (in string type, in core_idl::Problem _problem, in core_idl::Roadmap roadmap) raises (Error);
784  core_idl::PathOptimizer createPathOptimizer (in string type, in core_idl::Problem _problem) raises (Error);
785 
786  core_idl::ConfigValidation createConfigValidation (in string type, in pinocchio_idl::Device robot) raises (Error);
787  core_idl::PathValidation createPathValidation (in string type, in pinocchio_idl::Device robot, in value_type parameter) raises (Error);
788  core_idl::ConfigurationShooter createConfigurationShooter (in string type, in core_idl::Problem _problem) raises (Error);
789  core_idl::Distance createDistance (in string type, in core_idl::Problem _problem) raises (Error);
790  core_idl::SteeringMethod createSteeringMethod (in string type, in core_idl::Problem _problem) raises (Error);
791 
793  };
794  }; // interface Problem
795 }; // module hpp
796 #endif
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’&#39;.
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
Definition: paths.idl:22
To define and solve a path planning problem.
Definition: problem.idl:26
Definition: common-idl.hh:689
Definition: path_validations.idl:30
Definition: paths.idl:67