hpp-manipulation-corba  4.9.0
Corba server for manipulation planning
graph.idl
Go to the documentation of this file.
1 // Copyright (c) 2014, LAAS-CNRS
2 // Authors: Joseph Mirabel (joseph.mirabel@laas.fr)
3 //
4 // This file is part of hpp-manipulation.
5 // hpp-manipulation 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 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. If not, see <http://www.gnu.org/licenses/>.
16 
17 
18 #ifndef HPP_MANIPULATION_CORBA_GRAPH_IDL
19 #define HPP_MANIPULATION_CORBA_GRAPH_IDL
20 
22 #include <hpp/common.idl>
23 
24 module hpp {
25  module corbaserver {
26  module manipulation {
27  typedef sequence <Names_t> Namess_t;
28 
30  struct Rule {
33  boolean link;
34  };
35  typedef sequence<Rule> Rules;
36 
37  interface Graph {
40  long createGraph(in string graphName)
41  raises (Error);
42 
43  void deleteGraph(in string graphName)
44  raises (Error);
45 
48  void selectGraph(in string graphName)
49  raises (Error);
50 
52  void createSubGraph(in string subgraphName)
53  raises (Error);
54 
55  void setTargetNodeList(in ID graphId, in IDseq nodes)
56  raises (Error);
57 
65  long createNode (in long graphId, in string nodeName, in boolean waypoint, in long priority)
66  raises (Error);
67 
74  long createEdge (in long nodeFromId, in long nodeToId, in string edgeName, in long weight, in long isInNodeId)
75  raises (Error);
76 
80  void setContainingNode (in ID edgeId, in ID nodeId)
81  raises (Error);
82 
86  string getContainingNode (in ID edgeId)
87  raises (Error);
88 
93  long createWaypointEdge (in long nodeFromId, in long nodeToId,
94  in string edgeName, in long number,
95  in long weight, in long isInNode)
96  raises (Error);
97 
102  long getWaypoint (in long edgeId, in long index, out ID nodeId)
103  raises (Error);
104 
105  void setWaypoint (in ID waypointEdgeId, in long index,
106  in ID edgeId, in ID nodeId)
107  raises (Error);
108 
111  void getGraph (out GraphComp graph, out GraphElements elmts)
112  raises (Error);
113 
114  void getEdgeStat (in ID edgeId, out Names_t reasons, out intSeq freqs)
115  raises (Error);
116 
120  long getFrequencyOfNodeInRoadmap (in ID nodeId, out intSeq freqPerConnectedComponent)
121  raises (Error);
122 
128  boolean getConfigProjectorStats (in ID elmt, out ConfigProjStat config, out ConfigProjStat path)
129  raises (Error);
130 
137  long createLevelSetEdge(in long nodeFromId, in long nodeToId, in string edgeName, in long weight, in ID isInNodeId)
138  raises (Error);
139 
146  void addLevelSetFoliation (in long edgeId, in Names_t condNC,
147  in Names_t paramNC)
148  raises (Error);
149 
152  void resetConstraints(in long graphComponentId) raises (Error);
153 
155  void setNumericalConstraints (in long graphComponentId, in Names_t constraintNames, in Names_t passiveDofsNames)
156  raises (Error);
157 
164  void addNumericalConstraints (in long graphComponentId, in Names_t constraintNames, in Names_t passiveDofsNames)
165  raises (Error);
166 
170  void getNumericalConstraints (in long graphComponentId, out Names_t constraintNames)
171  raises (Error);
172 
174  void setNumericalConstraintsForPath (in long nodeId, in Names_t constraintNames, in Names_t passiveDofsNames)
175  raises (Error);
176 
183  void addNumericalConstraintsForPath (in long nodeId, in Names_t constraintNames, in Names_t passiveDofsNames)
184  raises (Error);
185 
190  void removeCollisionPairFromEdge (in ID edgeId, in string joint1,
191  in string joint2) raises (Error);
192 
196  void getNode (in floatSeq dofArray, out ID nodeId)
197  raises (Error);
198 
205  boolean applyNodeConstraints (in ID idComp, in floatSeq input, out floatSeq output,
206  out double residualError)
207  raises (Error);
208 
216  boolean applyEdgeLeafConstraints
217  (in ID idedge, in floatSeq qleaf, in floatSeq input,
218  out floatSeq output, out double residualError) raises (Error);
219 
227  boolean generateTargetConfig (in ID IDedge, in floatSeq qleaf,
228  in floatSeq input, out floatSeq output,
229  out double residualError)
230  raises (Error);
231 
241  boolean getConfigErrorForNode (in ID nodeId, in floatSeq config,
242  out floatSeq errorVector) raises (Error);
243 
255  boolean getConfigErrorForEdge (in ID EdgeId, in floatSeq config,
256  out floatSeq errorVector) raises (Error);
257 
269  boolean getConfigErrorForEdgeLeaf
270  (in ID EdgeId, in floatSeq leafConfig, in floatSeq config,
271  out floatSeq errorVector) raises (Error);
272 
284  boolean getConfigErrorForEdgeTarget
285  (in ID EdgeId, in floatSeq leafConfig, in floatSeq config,
286  out floatSeq errorVector) raises (Error);
287 
293  void displayNodeConstraints (in ID nodeId, out string constraints)
294  raises (Error);
295 
302  void displayEdgeTargetConstraints (in ID edgeId, out string constraints)
303  raises (Error);
304 
310  void displayEdgeConstraints (in ID edgeId, out string constraints)
311  raises (Error);
312 
318  void getNodesConnectedByEdge (in ID edgeId, out string from,
319  out string to) raises (Error);
320 
321  void display (in string filename)
322  raises (Error);
323 
324  void getHistogramValue (in ID edgeId, out floatSeq freq, out floatSeqSeq values)
325  raises (Error);
326 
327  void setShort (in ID edgeId, in boolean isShort)
328  raises (Error);
329 
330  boolean isShort (in ID edgeId)
331  raises (Error);
332 
362  // \par allows to create two separated notes.
375  long autoBuild (in string graphName,
376  in Names_t grippers, in Names_t objects,
377  in Namess_t handlesPerObject, in Namess_t contactsPerObject,
378  in Names_t envNames, in Rules rulesList)
379  raises (Error);
380 
384  void setWeight (in ID edgeID, in long weight)
385  raises (Error);
386 
390  long getWeight (in ID edgeID)
391  raises (Error);
392 
396  string getName (in ID elmtID)
397  raises (Error);
398 
400  void initialize ()
401  raises (Error);
402 
406  void getRelativeMotionMatrix (in ID edgeID, out intSeqSeq matrix)
407  raises (Error);
408 
415  void setSecurityMarginForEdge(in ID edgeID, in string joint1,
416  in string joint2, in double margin)
417  raises(Error);
418  }; // interface Graph
419  }; // module manipulation
420  }; // module corbaserver
421 }; // module hpp
422 
423 #endif // HPP_MANIPULATION_CORBA_GRAPH_IDL
Definition: gcommon.idl:38
Definition: gcommon.idl:31
Names_t handles
Definition: graph.idl:32
bool initialize(MeshCollisionTraversalNode< BV, RelativeTransformationIsIdentity > &node, BVHModel< BV > &model1, Transform3f &tf1, BVHModel< BV > &model2, Transform3f &tf2, CollisionResult &result, bool use_refit=false, bool refit_bottomup=false)
sequence< floatSeq > floatSeqSeq
boolean link
Definition: graph.idl:33
sequence< string > Names_t
sequence< long > intSeq
sequence< Names_t > Namess_t
Definition: graph.idl:27
sequence< Rule > Rules
Definition: graph.idl:35
Names_t grippers
Definition: graph.idl:31
long ID
Definition: gcommon.idl:23
sequence< ID > IDseq
Definition: gcommon.idl:24
std::ostream & display(std::ostream &os, const SE3 &m)
sequence< double > floatSeq
Definition: gcommon.idl:26
Describe a rule to link or not, a gripper and a handle.
Definition: graph.idl:30
sequence< intSeq > intSeqSeq