hpp-rbprm-corba  4.9.0
Corba server for reachability based planning
rbprmbuilder.idl
Go to the documentation of this file.
1 // Copyright (c) 2015 CNRS
2 // Author: Steve Tonneau
3 //
4 // This file is part of hpp-manipulation-corba.
5 // hpp-manipulation-corba is free software: you can redistribute it
6 // and/or modify it under the terms of the GNU Lesser General Public
7 // License as published by the Free Software Foundation, either version
8 // 3 of the License, or (at your option) any later version.
9 //
10 // hpp-manipulation-corba is distributed in the hope that it will be
11 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
12 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
13 // General Lesser Public License for more details. You should have
14 // received a copy of the GNU Lesser General Public License along with
15 // hpp-manipulation-corba. If not, see
16 // <http://www.gnu.org/licenses/>.
17 
18 #ifndef HPP_RBPRM_CORBA_BUILDER_IDL
19 # define HPP_RBPRM_CORBA_BUILDER_IDL
20 
21 # include <hpp/common.idl>
22 
23 module hpp
24 {
25  typedef sequence<floatSeqSeq> floatSeqSeqSeq;
26  module corbaserver {
27  module rbprm {
28 
29  interface RbprmBuilder
30  {
47  void loadRobotRomModel (in string romRobotName, in string rootJointType,
48  in string packageName, in string modelName,
49  in string urdfSuffix, in string srdfSuffix)
50  raises (Error);
51 
52 
54 
68  void loadRobotCompleteModel (in string trunkRobotName, in string rootJointType,
69  in string packageName, in string modelName,
70  in string urdfSuffix, in string srdfSuffix)
71  raises (Error);
72 
87  void loadFullBodyRobot (in string trunkRobotName, in string rootJointType,
88  in string packageName, in string modelName,
89  in string urdfSuffix, in string srdfSuffix, in string selectedProblem)
90  raises (Error);
91 
95  void loadFullBodyRobotFromExistingRobot ()
96  raises (Error);
97 
98  void selectFullBody (in string name) raises (Error);
99 
102  void setStaticStability(in boolean staticStability)
103  raises (Error);
104 
106  void setReferenceConfig(in floatSeq referenceConfig)
107  raises (Error);
108 
110  void setPostureWeights(in floatSeq postureWeights)
111  raises (Error);
112 
114  void usePosturalTaskContactCreation(in boolean use)
115  raises (Error);
116 
118  void setReferenceEndEffector(in string romName, in floatSeq ref)
119  raises (Error);
120 
127  void setFilter (in Names_t roms)
128  raises (Error);
129 
133  void initNewProblemSolver ()
134  raises (Error);
135 
142  void setAffordanceFilter(in string romName, in Names_t affordances) raises (Error);
143 
149  void boundSO3(in floatSeq limitszyx) raises (Error);
150 
155  double projectStateToCOM(in unsigned short stateId, in floatSeq com, in unsigned short max_num_sample) raises (Error);
156 
161  short cloneState(in unsigned short stateId) raises (Error);
162 
168  double projectStateToRoot(in unsigned short stateId, in floatSeq root, in floatSeq offset) raises (Error);
169 
170 
175  double setConfigAtState(in unsigned short stateId, in floatSeq config) raises (Error);
176 
177 
183  short createState(in floatSeq configuration, in Names_t contactLimbs) raises (Error);
184 
190  floatSeq getSampleConfig(in string sampleName, in unsigned long sampleId) raises (Error);
191 
192 
198  floatSeq getSamplePosition(in string sampleName, in unsigned long sampleId) raises (Error);
199 
205  floatSeqSeq getEffectorPosition(in string limbName, in floatSeq dofArray) raises (Error);
206 
210  unsigned short getNumSamples(in string limbName) raises (Error);
211 
215  floatSeq getOctreeNodeIds(in string limbName) raises (Error);
216 
222  double getSampleValue(in string limbName, in string valueName, in unsigned long sampleId) raises (Error);
223 
229  double getEffectorDistance(in unsigned short state1, in unsigned short state2) raises (Error);
230 
235  floatSeq generateContacts(in floatSeq dofArray, in floatSeq direction, in floatSeq acceleration, in double robustnessThreshold) raises (Error);
236 
241  short generateStateInContact(in floatSeq dofArray, in floatSeq direction, in floatSeq acceleration, in double robustnessThreshold) raises (Error);
242 
246  floatSeq generateGroundContact(in Names_t contactLimbs) raises (Error);
247 
254  floatSeq getContactSamplesIds(in string name, in floatSeq dofArray, in floatSeq direction) raises (Error);
255 
262  floatSeqSeq getContactSamplesProjected(in string name, in floatSeq dofArray, in floatSeq direction,
263  in unsigned short numSamples) raises (Error);
264 
270  short generateContactState(in unsigned short currentState, in string name, in floatSeq direction) raises (Error);
271 
276  floatSeq getSamplesIdsInOctreeNode(in string name, in double octreeNodeId) raises (Error);
277 
293  void addLimb(in string id, in string limb, in string effector, in floatSeq offset, in floatSeq normal,
294  in double x, in double y, in unsigned long samples, in string heuristicName,
295  in double resolution, in string contactType, in double disableEffectorCollision,
296  in double grasp,in floatSeq limbOffset,
297  in string kinematicConstraintsPath, in double kinematicConstraintsMin) raises (Error);
298 
304  void addNonContactingLimb(in string id, in string limb, in string effector, in unsigned long samples) raises (Error);
305 
313  void addLimbDatabase(in string databasepath, in string id, in string heuristicName, in double loadValues,
314  in double disableEffectorCollision,in double grasp) raises (Error);
315 
319  void setStartState(in floatSeq dofArray, in Names_t contactLimbs) raises (Error);
320 
323  void setStartStateId(in unsigned short stateId) raises (Error);
324 
327  void setEndStateId(in unsigned short stateId) raises (Error);
328 
333  floatSeq computeContactForConfig(in floatSeq dofArray, in string limbName) raises (Error);
334 
339  void setEndState(in floatSeq dofArray, in Names_t contactLimbs) raises (Error);
340 
345  floatSeqSeq computeContactPoints(in unsigned short stateId) raises (Error);
346 
351  floatSeqSeq computeContactPointsForLimb(in unsigned short stateId, in string limbname) raises (Error);
352 
357  floatSeqSeq computeContactPointsAtStateForLimb(in unsigned short stateId, in unsigned short isIntermediate, in string limbname) raises (Error);
358 
363  floatSeqSeq computeCenterOfContactAtStateForLimb(in unsigned short cId,in unsigned short isIntermediate, in string limbName) raises(Error);
364 
370  floatSeqSeq computeContactPointsAtState(in unsigned short stateId, in unsigned short isIntermediate) raises (Error);
371 
381  floatSeqSeq interpolate(in double timestep, in double path, in double robustnessTreshold, in unsigned short filterStates, in boolean testReachability, in boolean quasiStatic, in boolean erasePreviousStates) raises (Error);
382 
392  floatSeqSeq interpolateConfigs(in floatSeqSeq configs, in double robustnessTreshold, in unsigned short filterStates,in boolean testReachability, in boolean quasiStatic, in boolean erasePreviousStates) raises (Error);
393 
394 
400  floatSeqSeq getContactCone(in unsigned short stateId, in double friction) raises (Error);
401 
406  floatSeqSeq getContactIntermediateCone(in unsigned short stateId, in double friction) raises (Error);
407 
419  short generateRootPath(in floatSeqSeq rootPositions, in floatSeq q1, in floatSeq q2) raises (Error);
420 
433  short generateComTraj(in floatSeqSeq positions, in floatSeqSeq velocities, in floatSeqSeq accelerations, in double dt) raises (Error);
434 
442  short straightPath(in floatSeqSeq positions) raises (Error);
443 
448  short generateCurveTraj(in floatSeqSeq coefficients) raises (Error);
449 
455  short generateCurveTrajParts(in floatSeqSeq coefficients, in floatSeq partitions) raises (Error);
456 
467  short limbRRT(in unsigned short state1, in unsigned short state2, in unsigned short numOptimizations) raises (Error);
468 
480  short limbRRTFromRootPath(in unsigned short state1, in unsigned short state2, in unsigned short path, in unsigned short numOptimizations) raises (Error);
481 
485  short configToPath(in floatSeqSeq configs) raises (Error);
486 
498  short comRRT(in unsigned short state1, in unsigned short state2, in unsigned short comPath, in unsigned short numOptimizations) raises (Error);
499 
512  floatSeq comRRTFromPos(in unsigned short state1,
513  in unsigned short comTraj1,
514  in unsigned short comTraj2,
515  in unsigned short comTraj3,
516  in unsigned short numOptimizations) raises (Error);
517 
518 
532  floatSeq comRRTFromPosBetweenState(in unsigned short state1,in unsigned short state2,
533  in unsigned short comTraj1,
534  in unsigned short comTraj2,
535  in unsigned short comTraj3,
536  in unsigned short numOptimizations) raises (Error);
537 
538 
552  floatSeq effectorRRTFromPosBetweenState(in unsigned short state1,in unsigned short state2,
553  in unsigned short comTraj1,
554  in unsigned short comTraj2,
555  in unsigned short comTraj3,
556  in unsigned short numOptimizations) raises (Error);
557 
558 
571  floatSeq effectorRRT(in unsigned short state1,
572  in unsigned short comTraj1,
573  in unsigned short comTraj2,
574  in unsigned short comTraj3,
575  in unsigned short numOptimizations) raises (Error);
576 
577 
586  floatSeq effectorRRTOnePhase(in unsigned short state1, in unsigned short state2,
587  in unsigned short comTraj,
588  in unsigned short numOptimizations) raises (Error);
589 
597  floatSeqSeq generateEffectorBezierArray(in unsigned short state1, in unsigned short state2,
598  in unsigned short comTraj,
599  in unsigned short numOptimizations) raises (Error);
600 
601 
610  floatSeq comRRTOnePhase(in unsigned short state1, in unsigned short state2,
611  in unsigned short comTraj,
612  in unsigned short numOptimizations) raises (Error);
613 
614 
615 
628  floatSeq effectorRRTFromPath(in unsigned short state1, in unsigned short refPath,
629  in double path_from, in double path_to,
630  in unsigned short comTraj1,
631  in unsigned short comTraj2,
632  in unsigned short comTraj3,
633  in unsigned short numOptimizations,
634  in Names_t trackedEffectors) raises (Error);
635 
636 
637 
644  short generateEndEffectorBezier(in unsigned short state1,in unsigned short state2,
645  in unsigned short comTraj) raises (Error);
646 
654  floatSeq projectToCom(in unsigned short state, in floatSeq targetCom, in unsigned short max_num_sample) raises (Error);
655 
661  floatSeq getConfigAtState(in unsigned short state) raises (Error);
662 
666  short isLimbInContact(in string limbname, in unsigned short state1) raises (Error);
667 
672  short isLimbInContactIntermediary(in string limbname, in unsigned short state1) raises (Error);
673 
678  short computeIntermediary(in unsigned short state1, in unsigned short state2) raises (Error);
679 
682  short getNumStates() raises (Error);
683 
687  void saveComputedStates(in string filename) raises (Error);
688 
693  void saveLimbDatabase(in string limbname, in string filename) raises (Error);
694 
699  floatSeqSeq getOctreeBoxes(in string limbname, in floatSeq dofArray) raises (Error);
700 
705  floatSeq getOctreeBox(in string limbname, in double sampleId) raises (Error);
706 
711  floatSeq getOctreeTransform(in string limbname, in floatSeq dofArray) raises (Error);
712 
715  double isStateBalanced(in unsigned short state) raises (Error);
716 
723  short isConfigBalanced(in floatSeq config, in Names_t contacts, in double robustnessTreshold,in floatSeq CoM) raises (Error);
724 
729  void runSampleAnalysis(in string analysis, in double isstatic) raises (Error);
730 
737  floatSeq runLimbSampleAnalysis(in string limbname, in string analysis, in double isstatic) raises (Error);
738 
739  // call the heuristic function on each limb for the given configuration
740  floatSeq evaluateConfig(in floatSeq configuration, in floatSeq direction) raises (Error);
741 
742 
746  void dumpProfile(in string logFile) raises (Error);
747 
750  double getTimeAtState(in unsigned short stateId) raises (Error);
751 
755  Names_t getContactsVariations(in unsigned short stateIdFrom,in unsigned short stateIdTo) raises (Error);
756 
757 
761  Names_t getCollidingObstacleAtConfig(in floatSeq configuration,in string limbName) raises (Error);
762 
766  floatSeqSeq getContactSurfacesAtConfig(in floatSeq configuration,in string limbName) raises (Error);
767 
769  Names_t getAllLimbsNames() raises (Error);
783  short addNewContact(in unsigned short stateId, in string limbName, in floatSeq position, in floatSeq normal, in unsigned short max_num_sample, in boolean lockOtherJoints,in floatSeq rotation) raises (Error);
784 
790  short removeContact(in unsigned short stateId, in string limbName) raises (Error);
791 
792 
800  floatSeq computeTargetTransform(in string limbname, in floatSeq configuration, in floatSeq p, in floatSeq n) raises (Error);
801 
805  Names_t getEffectorsTrajectoriesNames(in unsigned short pathId)raises (Error);
806 
813  floatSeqSeqSeq getEffectorTrajectoryWaypoints(in unsigned short pathId,in string effectorName) raises (Error);
814 
818  floatSeqSeq getPathAsBezier(in unsigned short pathId)raises (Error);
819 
820 
821  boolean toggleNonContactingLimb(in string limbname)raises (Error);
822 
823  boolean areKinematicsConstraintsVerified(in floatSeq point)raises (Error);
824 
825  boolean areKinematicsConstraintsVerifiedForState(in unsigned short stateFrom,in floatSeq point)raises (Error);
826 
827  floatSeq isReachableFromState(in unsigned short stateFrom, in unsigned short stateTo, in boolean useIntermediateState)raises (Error);
828 
829  floatSeq isDynamicallyReachableFromState(in unsigned short stateFrom, in unsigned short stateTo,in boolean addPathPerPhase, in floatSeq timings,in short numPointsPerPhase)raises (Error);
830 
831 
832  }; // interface Robot
833  }; // module rbprm
834  }; // module corbaserver
835 }; // module hpp
836 
837 #endif // HPP_RBPRM_CORBA_BUILDER_IDL
Definition: server.hh:29
Definition: rbprmbuilder.idl:29
sequence< floatSeqSeq > floatSeqSeqSeq
Definition: rbprmbuilder.idl:25