hpp-manipulation-corba  4.12.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 {
31  Names_t grippers;
32  Names_t handles;
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)
156  raises (Error);
157 
161  void addNumericalConstraints (in long graphComponentId, in Names_t constraintNames)
162  raises (Error);
163 
167  void getNumericalConstraints (in long graphComponentId, out Names_t constraintNames)
168  raises (Error);
169 
171  void setNumericalConstraintsForPath (in long nodeId, in Names_t constraintNames)
172  raises (Error);
173 
177  void addNumericalConstraintsForPath (in long nodeId, in Names_t constraintNames)
178  raises (Error);
179 
184  void removeCollisionPairFromEdge (in ID edgeId, in string joint1,
185  in string joint2) raises (Error);
186 
190  void getNode (in floatSeq dofArray, out ID nodeId)
191  raises (Error);
192 
199  boolean applyNodeConstraints (in ID idComp, in floatSeq input, out floatSeq output,
200  out double residualError)
201  raises (Error);
202 
211  (in ID idedge, in floatSeq qleaf, in floatSeq input,
212  out floatSeq output, out double residualError) raises (Error);
213 
221  boolean generateTargetConfig (in ID IDedge, in floatSeq qleaf,
222  in floatSeq input, out floatSeq output,
223  out double residualError)
224  raises (Error);
225 
235  boolean getConfigErrorForNode (in ID nodeId, in floatSeq config,
236  out floatSeq errorVector) raises (Error);
237 
249  boolean getConfigErrorForEdge (in ID EdgeId, in floatSeq config,
250  out floatSeq errorVector) raises (Error);
251 
264  (in ID EdgeId, in floatSeq leafConfig, in floatSeq config,
265  out floatSeq errorVector) raises (Error);
266 
279  (in ID EdgeId, in floatSeq leafConfig, in floatSeq config,
280  out floatSeq errorVector) raises (Error);
281 
287  void displayNodeConstraints (in ID nodeId, out string constraints)
288  raises (Error);
289 
296  void displayEdgeTargetConstraints (in ID edgeId, out string constraints)
297  raises (Error);
298 
304  void displayEdgeConstraints (in ID edgeId, out string constraints)
305  raises (Error);
306 
312  void getNodesConnectedByEdge (in ID edgeId, out string from,
313  out string to) raises (Error);
314 
315  void display (in string filename)
316  raises (Error);
317 
318  void getHistogramValue (in ID edgeId, out floatSeq freq, out floatSeqSeq values)
319  raises (Error);
320 
321  void setShort (in ID edgeId, in boolean isShort)
322  raises (Error);
323 
324  boolean isShort (in ID edgeId)
325  raises (Error);
326 
356  // \par allows to create two separated notes.
369  long autoBuild (in string graphName,
370  in Names_t grippers, in Names_t objects,
371  in Namess_t handlesPerObject, in Namess_t contactsPerObject,
372  in Names_t envNames, in Rules rulesList)
373  raises (Error);
374 
378  void setWeight (in ID edgeID, in long weight)
379  raises (Error);
380 
384  long getWeight (in ID edgeID)
385  raises (Error);
386 
390  string getName (in ID elmtID)
391  raises (Error);
392 
394  void initialize ()
395  raises (Error);
396 
400  void getRelativeMotionMatrix (in ID edgeID, out intSeqSeq matrix)
401  raises (Error);
402 
409  void setSecurityMarginForEdge(in ID edgeID, in string joint1,
410  in string joint2, in double margin)
411  raises(Error);
412  }; // interface Graph
413  }; // module manipulation
414  }; // module corbaserver
415 }; // module hpp
416 
417 #endif // HPP_MANIPULATION_CORBA_GRAPH_IDL
string getContainingNode(in ID edgeId)
boolean generateTargetConfig(in ID IDedge, in floatSeq qleaf, in floatSeq input, out floatSeq output, out double residualError)
long createEdge(in long nodeFromId, in long nodeToId, in string edgeName, in long weight, in long isInNodeId)
void getGraph(out GraphComp graph, out GraphElements elmts)
void display(in string filename)
long getWaypoint(in long edgeId, in long index, out ID nodeId)
void initialize()
This must be called when the graph has been built.
void createSubGraph(in string subgraphName)
Create a subgraph of the constraint graph for one particular end-effector.
void displayEdgeTargetConstraints(in ID edgeId, out string constraints)
void addNumericalConstraintsForPath(in long nodeId, in Names_t constraintNames)
void addNumericalConstraints(in long graphComponentId, in Names_t constraintNames)
void resetConstraints(in long graphComponentId)
void setContainingNode(in ID edgeId, in ID nodeId)
long createGraph(in string graphName)
boolean getConfigErrorForEdge(in ID EdgeId, in floatSeq config, out floatSeq errorVector)
long createWaypointEdge(in long nodeFromId, in long nodeToId, in string edgeName, in long number, in long weight, in long isInNode)
boolean applyEdgeLeafConstraints(in ID idedge, in floatSeq qleaf, in floatSeq input, out floatSeq output, out double residualError)
void setNumericalConstraints(in long graphComponentId, in Names_t constraintNames)
boolean getConfigErrorForNode(in ID nodeId, in floatSeq config, out floatSeq errorVector)
boolean applyNodeConstraints(in ID idComp, in floatSeq input, out floatSeq output, out double residualError)
void getEdgeStat(in ID edgeId, out Names_t reasons, out intSeq freqs)
void addLevelSetFoliation(in long edgeId, in Names_t condNC, in Names_t paramNC)
void displayNodeConstraints(in ID nodeId, out string constraints)
void getNodesConnectedByEdge(in ID edgeId, out string from, out string to)
long autoBuild(in string graphName, in Names_t grippers, in Names_t objects, in Namess_t handlesPerObject, in Namess_t contactsPerObject, in Names_t envNames, in Rules rulesList)
void setWaypoint(in ID waypointEdgeId, in long index, in ID edgeId, in ID nodeId)
void getNode(in floatSeq dofArray, out ID nodeId)
void getNumericalConstraints(in long graphComponentId, out Names_t constraintNames)
void setWeight(in ID edgeID, in long weight)
void setShort(in ID edgeId, in boolean isShort)
void displayEdgeConstraints(in ID edgeId, out string constraints)
void selectGraph(in string graphName)
void deleteGraph(in string graphName)
long createNode(in long graphId, in string nodeName, in boolean waypoint, in long priority)
boolean getConfigProjectorStats(in ID elmt, out ConfigProjStat config, out ConfigProjStat path)
void setTargetNodeList(in ID graphId, in IDseq nodes)
void getHistogramValue(in ID edgeId, out floatSeq freq, out floatSeqSeq values)
boolean getConfigErrorForEdgeTarget(in ID EdgeId, in floatSeq leafConfig, in floatSeq config, out floatSeq errorVector)
long getFrequencyOfNodeInRoadmap(in ID nodeId, out intSeq freqPerConnectedComponent)
boolean getConfigErrorForEdgeLeaf(in ID EdgeId, in floatSeq leafConfig, in floatSeq config, out floatSeq errorVector)
long createLevelSetEdge(in long nodeFromId, in long nodeToId, in string edgeName, in long weight, in ID isInNodeId)
void setNumericalConstraintsForPath(in long nodeId, in Names_t constraintNames)
void removeCollisionPairFromEdge(in ID edgeId, in string joint1, in string joint2)
sequence< Rule > Rules
Definition: graph.idl:35
sequence< Names_t > Namess_t
Definition: graph.idl:27
Definition: client.hh:25
long ID
Definition: gcommon.idl:23
sequence< ID > IDseq
Definition: gcommon.idl:24
Definition: gcommon.idl:26
Definition: gcommon.idl:31
Definition: gcommon.idl:38
Describe a rule to link or not, a gripper and a handle.
Definition: graph.idl:30
Names_t handles
Definition: graph.idl:32
boolean link
Definition: graph.idl:33
Names_t grippers
Definition: graph.idl:31