18 #ifndef HPP_MANIPULATION_CORBA_GRAPH_IDL
19 #define HPP_MANIPULATION_CORBA_GRAPH_IDL
22 #include <hpp/common.idl>
65 long createNode (in
long graphId, in
string nodeName, in
boolean waypoint, in
long priority)
74 long createEdge (in
long nodeFromId, in
long nodeToId, in
string edgeName, in
long weight, in
long isInNodeId)
94 in
string edgeName, in
long number,
95 in
long weight, in
long isInNode)
106 in
ID edgeId, in
ID nodeId)
137 long createLevelSetEdge(in
long nodeFromId, in
long nodeToId, in
string edgeName, in
long weight, in
ID isInNodeId)
185 in
string joint2) raises (Error);
200 out
double residualError)
211 (in
ID idedge, in floatSeq qleaf, in floatSeq input,
212 out floatSeq output, out
double residualError) raises (Error);
222 in floatSeq input, out floatSeq output,
223 out
double residualError)
236 out floatSeq errorVector) raises (Error);
250 out floatSeq errorVector) raises (Error);
264 (in
ID EdgeId, in floatSeq leafConfig, in floatSeq config,
265 out floatSeq errorVector) raises (Error);
279 (in
ID EdgeId, in floatSeq leafConfig, in floatSeq config,
280 out floatSeq errorVector) raises (Error);
313 out
string to) raises (Error);
370 in Names_t grippers, in Names_t objects,
372 in Names_t envNames, in
Rules rulesList)
400 void getRelativeMotionMatrix (in
ID edgeID, out intSeqSeq matrix)
409 void setSecurityMarginForEdge(in
ID edgeID, in
string joint1,
410 in
string joint2, in
double margin)
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)
long getWeight(in ID edgeID)
boolean isShort(in ID edgeId)
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)
string getName(in ID elmtID)
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
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