hpp-manipulation-corba 5.2.0
Corba server for manipulation planning
Loading...
Searching...
No Matches
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// Redistribution and use in source and binary forms, with or without
5// modification, are permitted provided that the following conditions are
6// met:
7//
8// 1. Redistributions of source code must retain the above copyright
9// notice, this list of conditions and the following disclaimer.
10//
11// 2. Redistributions in binary form must reproduce the above copyright
12// notice, this list of conditions and the following disclaimer in the
13// documentation and/or other materials provided with the distribution.
14//
15// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
16// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
17// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
18// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
19// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
20// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
21// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
22// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
23// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
25// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
26// DAMAGE.
27
28
29#ifndef HPP_MANIPULATION_CORBA_GRAPH_IDL
30#define HPP_MANIPULATION_CORBA_GRAPH_IDL
31
33#include <hpp/common.idl>
34
35module hpp {
36 module corbaserver {
37 module manipulation {
38 typedef sequence <Names_t> Namess_t;
39
41 struct Rule {
42 Names_t grippers;
43 Names_t handles;
44 boolean link;
45 };
46 typedef sequence<Rule> Rules;
47
48 interface Graph {
51 long createGraph(in string graphName)
52 raises (Error);
53
54 void deleteGraph(in string graphName)
55 raises (Error);
56
59 void selectGraph(in string graphName)
60 raises (Error);
61
63 void createSubGraph(in string subgraphName)
64 raises (Error);
65
66 void setTargetNodeList(in ID graphId, in IDseq nodes)
67 raises (Error);
68
76 long createNode (in long graphId, in string nodeName, in boolean waypoint, in long priority)
77 raises (Error);
78
85 long createEdge (in long nodeFromId, in long nodeToId, in string edgeName, in long weight, in long isInNodeId)
86 raises (Error);
87
91 void setContainingNode (in ID edgeId, in ID nodeId)
92 raises (Error);
93
97 string getContainingNode (in ID edgeId)
98 raises (Error);
99
104 long createWaypointEdge (in long nodeFromId, in long nodeToId,
105 in string edgeName, in long number,
106 in long weight, in long isInNode)
107 raises (Error);
108
113 long getWaypoint (in long edgeId, in long index, out ID nodeId)
114 raises (Error);
115
116 void setWaypoint (in ID waypointEdgeId, in long index,
117 in ID edgeId, in ID nodeId)
118 raises (Error);
119
122 void getGraph (out GraphComp graph, out GraphElements elmts)
123 raises (Error);
124
125 void getEdgeStat (in ID edgeId, out Names_t reasons, out intSeq freqs)
126 raises (Error);
127
131 long getFrequencyOfNodeInRoadmap (in ID nodeId, out intSeq freqPerConnectedComponent)
132 raises (Error);
133
139 boolean getConfigProjectorStats (in ID elmt, out ConfigProjStat config, out ConfigProjStat path)
140 raises (Error);
141
148 long createLevelSetEdge(in long nodeFromId, in long nodeToId, in string edgeName, in long weight, in ID isInNodeId)
149 raises (Error);
150
157 void addLevelSetFoliation (in long edgeId, in Names_t condNC,
158 in Names_t paramNC)
159 raises (Error);
160
163 void resetConstraints(in long graphComponentId) raises (Error);
164
166 void setNumericalConstraints (in long graphComponentId, in Names_t constraintNames)
167 raises (Error);
168
172 void addNumericalConstraints (in long graphComponentId, in Names_t constraintNames)
173 raises (Error);
174
178 void getNumericalConstraints (in long graphComponentId, out Names_t constraintNames)
179 raises (Error);
180
182 void setNumericalConstraintsForPath (in long nodeId, in Names_t constraintNames)
183 raises (Error);
184
188 void addNumericalConstraintsForPath (in long nodeId, in Names_t constraintNames)
189 raises (Error);
190
195 void removeCollisionPairFromEdge (in ID edgeId, in string joint1,
196 in string joint2) raises (Error);
197
201 void getNode (in floatSeq dofArray, out ID nodeId)
202 raises (Error);
203
210 boolean applyNodeConstraints (in ID idComp, in floatSeq input, out floatSeq output,
211 out double residualError)
212 raises (Error);
213
222 (in ID idedge, in floatSeq qleaf, in floatSeq input,
223 out floatSeq output, out double residualError) raises (Error);
224
232 boolean generateTargetConfig (in ID IDedge, in floatSeq qleaf,
233 in floatSeq input, out floatSeq output,
234 out double residualError)
235 raises (Error);
236
246 boolean getConfigErrorForNode (in ID nodeId, in floatSeq config,
247 out floatSeq errorVector) raises (Error);
248
260 boolean getConfigErrorForEdge (in ID EdgeId, in floatSeq config,
261 out floatSeq errorVector) raises (Error);
262
275 (in ID EdgeId, in floatSeq leafConfig, in floatSeq config,
276 out floatSeq errorVector) raises (Error);
277
290 (in ID EdgeId, in floatSeq leafConfig, in floatSeq config,
291 out floatSeq errorVector) raises (Error);
292
298 void displayNodeConstraints (in ID nodeId, out string constraints)
299 raises (Error);
300
307 void displayEdgeTargetConstraints (in ID edgeId, out string constraints)
308 raises (Error);
309
315 void displayEdgeConstraints (in ID edgeId, out string constraints)
316 raises (Error);
317
323 void getNodesConnectedByEdge (in ID edgeId, out string from,
324 out string to) raises (Error);
325
326 void display (in string filename)
327 raises (Error);
328
329 void getHistogramValue (in ID edgeId, out floatSeq freq, out floatSeqSeq values)
330 raises (Error);
331
332 void setShort (in ID edgeId, in boolean isShort)
333 raises (Error);
334
335 boolean isShort (in ID edgeId)
336 raises (Error);
337
367 // \par allows to create two separated notes.
380 long autoBuild (in string graphName,
381 in Names_t grippers, in Names_t objects,
382 in Namess_t handlesPerObject, in Namess_t contactsPerObject,
383 in Names_t envNames, in Rules rulesList)
384 raises (Error);
385
389 void setWeight (in ID edgeID, in long weight)
390 raises (Error);
391
395 long getWeight (in ID edgeID)
396 raises (Error);
397
401 string getName (in ID elmtID)
402 raises (Error);
403
406 raises (Error);
407
411 void getRelativeMotionMatrix (in ID edgeID, out intSeqSeq matrix)
412 raises (Error);
413
420 void setSecurityMarginForEdge(in ID edgeID, in string joint1,
421 in string joint2, in double margin)
422 raises(Error);
423
429 void getSecurityMarginMatrixForEdge(in ID edgeID,
430 out floatSeqSeq margin)
431 raises(Error);
432
433 }; // interface Graph
434 }; // module manipulation
435 }; // module corbaserver
436}; // module hpp
437
438#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:46
sequence< Names_t > Namess_t
Definition graph.idl:38
Definition client.hh:46
long ID
Definition gcommon.idl:34
sequence< ID > IDseq
Definition gcommon.idl:35
Definition problem_solver.py:1
Definition gcommon.idl:37
Definition gcommon.idl:42
Definition gcommon.idl:49
Describe a rule to link or not, a gripper and a handle.
Definition graph.idl:41
Names_t handles
Definition graph.idl:43
boolean link
Definition graph.idl:44
Names_t grippers
Definition graph.idl:42