hpp-rbprm-corba  4.12.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  {
41  void loadRobotRomModel (in string robotName, in string rootJointType,
42  in string urdfName)
43  raises (Error);
44 
45 
47 
58  void loadRobotCompleteModel (in string robotName, in string rootJointType,
59  in string urdfName, in string srdfName)
60  raises (Error);
61 
76  void loadFullBodyRobot (in string robotName, in string rootJointType,
77  in string urdfName, in string srdfName, in string selectedProblem)
78  raises (Error);
79 
83  void loadFullBodyRobotFromExistingRobot ()
84  raises (Error);
85 
86  void selectFullBody (in string name) raises (Error);
87 
90  void setStaticStability(in boolean staticStability)
91  raises (Error);
92 
94  void setReferenceConfig(in floatSeq referenceConfig)
95  raises (Error);
96 
98  void setPostureWeights(in floatSeq postureWeights)
99  raises (Error);
100 
102  void usePosturalTaskContactCreation(in boolean use)
103  raises (Error);
104 
106  void setReferenceEndEffector(in string romName, in floatSeq ref)
107  raises (Error);
108 
115  void setFilter (in Names_t roms)
116  raises (Error);
117 
121  void initNewProblemSolver ()
122  raises (Error);
123 
130  void setAffordanceFilter(in string romName, in Names_t affordances) raises (Error);
131 
137  void boundSO3(in floatSeq limitszyx) raises (Error);
138 
143  double projectStateToCOM(in unsigned short stateId, in floatSeq com, in unsigned short max_num_sample) raises (Error);
144 
149  short cloneState(in unsigned short stateId) raises (Error);
150 
156  double projectStateToRoot(in unsigned short stateId, in floatSeq root, in floatSeq offset) raises (Error);
157 
158 
163  double setConfigAtState(in unsigned short stateId, in floatSeq config) raises (Error);
164 
165 
171  short createState(in floatSeq configuration, in Names_t contactLimbs) raises (Error);
172 
178  floatSeq getSampleConfig(in string sampleName, in unsigned long sampleId) raises (Error);
179 
180 
186  floatSeq getSamplePosition(in string sampleName, in unsigned long sampleId) raises (Error);
187 
193  floatSeqSeq getEffectorPosition(in string limbName, in floatSeq dofArray) raises (Error);
194 
198  unsigned short getNumSamples(in string limbName) raises (Error);
199 
203  floatSeq getOctreeNodeIds(in string limbName) raises (Error);
204 
210  double getSampleValue(in string limbName, in string valueName, in unsigned long sampleId) raises (Error);
211 
217  double getEffectorDistance(in unsigned short state1, in unsigned short state2) raises (Error);
218 
223  floatSeq generateContacts(in floatSeq dofArray, in floatSeq direction, in floatSeq acceleration, in double robustnessThreshold) raises (Error);
224 
229  short generateStateInContact(in floatSeq dofArray, in floatSeq direction, in floatSeq acceleration, in double robustnessThreshold) raises (Error);
230 
234  floatSeq generateGroundContact(in Names_t contactLimbs) raises (Error);
235 
242  floatSeq getContactSamplesIds(in string name, in floatSeq dofArray, in floatSeq direction) raises (Error);
243 
250  floatSeqSeq getContactSamplesProjected(in string name, in floatSeq dofArray, in floatSeq direction,
251  in unsigned short numSamples) raises (Error);
252 
258  short generateContactState(in unsigned short currentState, in string name, in floatSeq direction) raises (Error);
259 
264  floatSeq getSamplesIdsInOctreeNode(in string name, in double octreeNodeId) raises (Error);
265 
281  void addLimb(in string id, in string limb, in string effector, in floatSeq offset, in floatSeq normal,
282  in double x, in double y, in unsigned long samples, in string heuristicName,
283  in double resolution, in string contactType, in double disableEffectorCollision,
284  in double grasp,in floatSeq limbOffset,
285  in string kinematicConstraintsPath, in double kinematicConstraintsMin) raises (Error);
286 
292  void addNonContactingLimb(in string id, in string limb, in string effector, in unsigned long samples) raises (Error);
293 
301  void addLimbDatabase(in string databasepath, in string id, in string heuristicName, in double loadValues,
302  in double disableEffectorCollision,in double grasp) raises (Error);
303 
307  void setStartState(in floatSeq dofArray, in Names_t contactLimbs) raises (Error);
308 
311  void setStartStateId(in unsigned short stateId) raises (Error);
312 
315  void setEndStateId(in unsigned short stateId) raises (Error);
316 
321  floatSeq computeContactForConfig(in floatSeq dofArray, in string limbName) raises (Error);
322 
327  void setEndState(in floatSeq dofArray, in Names_t contactLimbs) raises (Error);
328 
333  floatSeqSeq computeContactPoints(in unsigned short stateId) raises (Error);
334 
339  floatSeqSeq computeContactPointsForLimb(in unsigned short stateId, in string limbname) raises (Error);
340 
345  floatSeqSeq computeContactPointsAtStateForLimb(in unsigned short stateId, in unsigned short isIntermediate, in string limbname) raises (Error);
346 
351  floatSeqSeq computeCenterOfContactAtStateForLimb(in unsigned short cId,in unsigned short isIntermediate, in string limbName) raises(Error);
352 
358  floatSeqSeq computeContactPointsAtState(in unsigned short stateId, in unsigned short isIntermediate) raises (Error);
359 
369  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);
370 
381  floatSeqSeq interpolateConfigs(in floatSeqSeq configs, in double robustnessTreshold, in unsigned short filterStates,in boolean testReachability, in boolean quasiStatic, in boolean erasePreviousStates) raises (Error);
382 
383 
389  floatSeqSeq getContactCone(in unsigned short stateId, in double friction) raises (Error);
390 
395  floatSeqSeq getContactIntermediateCone(in unsigned short stateId, in double friction) raises (Error);
396 
408  short generateRootPath(in floatSeqSeq rootPositions, in floatSeq q1, in floatSeq q2) raises (Error);
409 
422  short generateComTraj(in floatSeqSeq positions, in floatSeqSeq velocities, in floatSeqSeq accelerations, in double dt) raises (Error);
423 
431  short straightPath(in floatSeqSeq positions) raises (Error);
432 
437  short generateCurveTraj(in floatSeqSeq coefficients) raises (Error);
438 
444  short generateCurveTrajParts(in floatSeqSeq coefficients, in floatSeq partitions) raises (Error);
445 
456  short limbRRT(in unsigned short state1, in unsigned short state2, in unsigned short numOptimizations) raises (Error);
457 
469  short limbRRTFromRootPath(in unsigned short state1, in unsigned short state2, in unsigned short path, in unsigned short numOptimizations) raises (Error);
470 
474  short configToPath(in floatSeqSeq configs) raises (Error);
475 
487  short comRRT(in unsigned short state1, in unsigned short state2, in unsigned short comPath, in unsigned short numOptimizations) raises (Error);
488 
501  floatSeq comRRTFromPos(in unsigned short state1,
502  in unsigned short comTraj1,
503  in unsigned short comTraj2,
504  in unsigned short comTraj3,
505  in unsigned short numOptimizations) raises (Error);
506 
507 
521  floatSeq comRRTFromPosBetweenState(in unsigned short state1,in unsigned short state2,
522  in unsigned short comTraj1,
523  in unsigned short comTraj2,
524  in unsigned short comTraj3,
525  in unsigned short numOptimizations) raises (Error);
526 
527 
541  floatSeq effectorRRTFromPosBetweenState(in unsigned short state1,in unsigned short state2,
542  in unsigned short comTraj1,
543  in unsigned short comTraj2,
544  in unsigned short comTraj3,
545  in unsigned short numOptimizations) raises (Error);
546 
547 
560  floatSeq effectorRRT(in unsigned short state1,
561  in unsigned short comTraj1,
562  in unsigned short comTraj2,
563  in unsigned short comTraj3,
564  in unsigned short numOptimizations) raises (Error);
565 
566 
575  floatSeq effectorRRTOnePhase(in unsigned short state1, in unsigned short state2,
576  in unsigned short comTraj,
577  in unsigned short numOptimizations) raises (Error);
578 
586  floatSeqSeq generateEffectorBezierArray(in unsigned short state1, in unsigned short state2,
587  in unsigned short comTraj,
588  in unsigned short numOptimizations) raises (Error);
589 
590 
599  floatSeq comRRTOnePhase(in unsigned short state1, in unsigned short state2,
600  in unsigned short comTraj,
601  in unsigned short numOptimizations) raises (Error);
602 
603 
604 
617  floatSeq effectorRRTFromPath(in unsigned short state1, in unsigned short refPath,
618  in double path_from, in double path_to,
619  in unsigned short comTraj1,
620  in unsigned short comTraj2,
621  in unsigned short comTraj3,
622  in unsigned short numOptimizations,
623  in Names_t trackedEffectors) raises (Error);
624 
625 
626 
633  short generateEndEffectorBezier(in unsigned short state1,in unsigned short state2,
634  in unsigned short comTraj) raises (Error);
635 
643  floatSeq projectToCom(in unsigned short state, in floatSeq targetCom, in unsigned short max_num_sample) raises (Error);
644 
650  floatSeq getConfigAtState(in unsigned short state) raises (Error);
651 
655  short isLimbInContact(in string limbname, in unsigned short state1) raises (Error);
656 
661  short isLimbInContactIntermediary(in string limbname, in unsigned short state1) raises (Error);
662 
667  short computeIntermediary(in unsigned short state1, in unsigned short state2) raises (Error);
668 
671  short getNumStates() raises (Error);
672 
676  void saveComputedStates(in string filename) raises (Error);
677 
682  void saveLimbDatabase(in string limbname, in string filename) raises (Error);
683 
688  floatSeqSeq getOctreeBoxes(in string limbname, in floatSeq dofArray) raises (Error);
689 
694  floatSeq getOctreeBox(in string limbname, in double sampleId) raises (Error);
695 
700  floatSeq getOctreeTransform(in string limbname, in floatSeq dofArray) raises (Error);
701 
704  double isStateBalanced(in unsigned short state) raises (Error);
705 
712  short isConfigBalanced(in floatSeq config, in Names_t contacts, in double robustnessTreshold,in floatSeq CoM) raises (Error);
713 
718  void runSampleAnalysis(in string analysis, in double isstatic) raises (Error);
719 
726  floatSeq runLimbSampleAnalysis(in string limbname, in string analysis, in double isstatic) raises (Error);
727 
728  // call the heuristic function on each limb for the given configuration
729  floatSeq evaluateConfig(in floatSeq configuration, in floatSeq direction) raises (Error);
730 
731 
735  void dumpProfile(in string logFile) raises (Error);
736 
739  double getTimeAtState(in unsigned short stateId) raises (Error);
740 
744  Names_t getContactsVariations(in unsigned short stateIdFrom,in unsigned short stateIdTo) raises (Error);
745 
746 
750  Names_t getCollidingObstacleAtConfig(in floatSeq configuration,in string limbName) raises (Error);
751 
755  floatSeqSeq getContactSurfacesAtConfig(in floatSeq configuration,in string limbName) raises (Error);
756 
758  Names_t getAllLimbsNames() raises (Error);
772  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);
773 
779  short removeContact(in unsigned short stateId, in string limbName) raises (Error);
780 
781 
789  floatSeq computeTargetTransform(in string limbname, in floatSeq configuration, in floatSeq p, in floatSeq n) raises (Error);
790 
794  Names_t getEffectorsTrajectoriesNames(in unsigned short pathId)raises (Error);
795 
802  floatSeqSeqSeq getEffectorTrajectoryWaypoints(in unsigned short pathId,in string effectorName) raises (Error);
803 
807  floatSeqSeq getPathAsBezier(in unsigned short pathId)raises (Error);
808 
809 
810  boolean toggleNonContactingLimb(in string limbname)raises (Error);
811 
812  boolean areKinematicsConstraintsVerified(in floatSeq point)raises (Error);
813 
814  boolean areKinematicsConstraintsVerifiedForState(in unsigned short stateFrom,in floatSeq point)raises (Error);
815 
816  floatSeq isReachableFromState(in unsigned short stateFrom, in unsigned short stateTo, in boolean useIntermediateState)raises (Error);
817 
818  floatSeq isDynamicallyReachableFromState(in unsigned short stateFrom, in unsigned short stateTo,in boolean addPathPerPhase, in floatSeq timings,in short numPointsPerPhase)raises (Error);
819 
820 
821  }; // interface Robot
822  }; // module rbprm
823  }; // module corbaserver
824 }; // module hpp
825 
826 #endif // HPP_RBPRM_CORBA_BUILDER_IDL
Definition: server.hh:29
Definition: rbprmbuilder.idl:29
sequence< floatSeqSeq > floatSeqSeqSeq
Definition: rbprmbuilder.idl:25