import"/home/jmirabel/devel/demo/src/hpp-manipulation-corba/idl/hpp/corbaserver/manipulation/graph.idl";
Public Member Functions | |
long | createGraph (in string graphName) raises (Error) |
Initialize the graph of constraints and add it to the ProblemSolver map. More... | |
void | deleteGraph (in string graphName) raises (Error) |
void | selectGraph (in string graphName) raises (Error) |
Select the graph of contraints from the ProblemSolver map. More... | |
long | createSubGraph (in string subgraphName) raises (Error) |
Create a subgraph of the constraint graph for one particular end-effector. More... | |
void | setTargetNodeList (in ID subgraph, in IDseq nodes) raises (Error) |
long | createNode (in long subGraphId, in string nodeName, in boolean waypoint, in long priority) raises (Error) |
Add a node to the graph. More... | |
long | createEdge (in long nodeFromId, in long nodeToId, in string edgeName, in long weight, in long isInNodeId) raises (Error) |
Add an edge between two nodes of the graph. More... | |
void | setContainingNode (in ID edgeId, in ID nodeId) raises (Error) |
Set in which node an edge is. More... | |
string | getContainingNode (in ID edgeId) raises (Error) |
Get in which node an edge is. More... | |
long | createWaypointEdge (in long nodeFromId, in long nodeToId, in string edgeName, in long number, in long weight, in long isInNode) raises (Error) |
Add an edge with waypoint between two nodes of the graph. More... | |
long | getWaypoint (in long edgeId, in long index, out ID nodeId) raises (Error) |
Get waypoint IDs of an edge. More... | |
void | setWaypoint (in ID waypointEdgeId, in long index, in ID edgeId, in ID nodeId) raises (Error) |
void | getGraph (out GraphComp graph, out GraphElements elmts) raises (Error) |
Get full graph. More... | |
void | getEdgeStat (in ID edgeId, out Names_t reasons, out intSeq freqs) raises (Error) |
long | getFrequencyOfNodeInRoadmap (in ID nodeId, out intSeq freqPerConnectedComponent) raises (Error) |
Get the number of nodes in the roadmap being in the node nodeId of the graph. More... | |
boolean | getConfigProjectorStats (in ID elmt, out ConfigProjStat config, out ConfigProjStat path) raises (Error) |
Get config projector statistics. More... | |
long | createLevelSetEdge (in long nodeFromId, in long nodeToId, in string edgeName, in long weight, in ID isInNodeId) raises (Error) |
Add an edge of type LevelSetEdge between two nodes. More... | |
void | setLevelSetFoliation (in long edgeId, in Names_t condNC, in Names_t condLJ, in Names_t paramNC, in Names_t paramPassiveJoints, in Names_t paramLJ) raises (Error) |
void | addLevelSetFoliation (in long edgeId, in Names_t condNC, in Names_t condLJ, in Names_t paramNC, in Names_t paramPassiveJoints, in Names_t paramLJ) raises (Error) |
Add the constraints to a LevelSetEdge that create the foliation. More... | |
void | resetConstraints (in long graphComponentId) raises (Error) |
Reset the numerical constraints and the locked joints of a component. More... | |
void | setNumericalConstraints (in long graphComponentId, in Names_t constraintNames, in Names_t passiveDofsNames) raises (Error) |
void | addNumericalConstraints (in long graphComponentId, in Names_t constraintNames, in Names_t passiveDofsNames) raises (Error) |
Add the numerical constraints to a component. More... | |
void | getNumericalConstraints (in long graphComponentId, out Names_t constraintNames) raises (Error) |
Get the list of numerical constraints applied to a component. More... | |
void | getLockedJoints (in long graphComponentId, out Names_t constraintNames) raises (Error) |
Get the list of locked joints in a component. More... | |
void | setNumericalConstraintsForPath (in long nodeId, in Names_t constraintNames, in Names_t passiveDofsNames) raises (Error) |
void | addNumericalConstraintsForPath (in long nodeId, in Names_t constraintNames, in Names_t passiveDofsNames) raises (Error) |
Add the numerical constraints for path to a node. More... | |
void | setLockedDofConstraints (in long graphComponentId, in Names_t constraintNames) raises (Error) |
void | addLockedDofConstraints (in long graphComponentId, in Names_t constraintNames) raises (Error) |
Add the LockedDof constraints to a component. More... | |
void | removeCollisionPairFromEdge (in ID edgeId, in string joint1, in string joint2) raises (Error) |
Remove collision pairs from an edge. More... | |
void | getNode (in floatSeq dofArray, out ID nodeId) raises (Error) |
Get the node corresponding to the state of the configuration. More... | |
boolean | getConfigErrorForNode (in ID nodeId, in floatSeq config, out floatSeq errorVector) raises (Error) |
Get error of a config with respect to a node constraint. More... | |
boolean | getConfigErrorForEdge (in ID EdgeId, in floatSeq config, out floatSeq errorVector) raises (Error) |
Get error of a config with respect to an edge constraint. More... | |
boolean | getConfigErrorForEdgeLeaf (in ID EdgeId, in floatSeq leafConfig, in floatSeq config, out floatSeq errorVector) raises (Error) |
Get error of a config with respect to an edge foliation leaf. More... | |
boolean | getConfigErrorForEdgeTarget (in ID EdgeId, in floatSeq leafConfig, in floatSeq config, out floatSeq errorVector) raises (Error) |
Get error of a config with respect to the target of an edge foliation leaf. More... | |
void | displayNodeConstraints (in ID nodeId, out string constraints) raises (Error) |
Print set of constraints relative to a node in a string. More... | |
void | displayEdgeTargetConstraints (in ID edgeId, out string constraints) raises (Error) |
Print set of constraints relative to an edge in a string. More... | |
void | displayEdgeConstraints (in ID edgeId, out string constraints) raises (Error) |
Print set of constraints relative to an edge in a string. More... | |
void | getNodesConnectedByEdge (in ID edgeId, out string from, out string to) raises (Error) |
Get nodes connected by an edge. More... | |
void | display (in string filename) raises (Error) |
void | getHistogramValue (in ID edgeId, out floatSeq freq, out floatSeqSeq values) raises (Error) |
void | setShort (in ID edgeId, in boolean isShort) raises (Error) |
boolean | isShort (in ID edgeId) raises (Error) |
intSeq | 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) raises (Error) |
Automatically build a constraint graph. More... | |
void | setWeight (in ID edgeID, in long weight) raises (Error) |
long | getWeight (in ID edgeID) raises (Error) |
string | getName (in ID elmtID) raises (Error) |
void | initialize () raises (Error) |
This must be called when the graph has been built. More... | |
void | getRelativeMotionMatrix (in ID edgeID, out intSeqSeq matrix) raises (Error) |
void hpp::corbaserver::manipulation::Graph::addLevelSetFoliation | ( | in long | edgeId, |
in Names_t | condNC, | ||
in Names_t | condLJ, | ||
in Names_t | paramNC, | ||
in Names_t | paramPassiveJoints, | ||
in Names_t | paramLJ | ||
) | |||
raises | ( | Error | |
) |
Add the constraints to a LevelSetEdge that create the foliation.
edgeId | if of a LevelSetEdge of the graph. |
condNC,condLJ | numerical constraints and locked joints that define the foliated manifold |
paramNC,paramPassiveJoints,paramLJ | numerical constraints and locked joints that parametrize the foliation |
Referenced by manipulation.constraint_graph.ConstraintGraph::setLevelSetFoliation().
void hpp::corbaserver::manipulation::Graph::addLockedDofConstraints | ( | in long | graphComponentId, |
in Names_t | constraintNames | ||
) | |||
raises | ( | Error | |
) |
Add the LockedDof constraints to a component.
graphComponentId | ID of the component. |
constraintNames | is an array of names of constraints in the ProblemSolver map. |
void hpp::corbaserver::manipulation::Graph::addNumericalConstraints | ( | in long | graphComponentId, |
in Names_t | constraintNames, | ||
in Names_t | passiveDofsNames | ||
) | |||
raises | ( | Error | |
) |
Add the numerical constraints to a component.
graphComponentId | ID of the component. |
constraintNames | is an array of names of constraints in the ProblemSolver map. |
passiveDofsNames | array of names of vector of passive dofs in the ProblemSolver map. |
void hpp::corbaserver::manipulation::Graph::addNumericalConstraintsForPath | ( | in long | nodeId, |
in Names_t | constraintNames, | ||
in Names_t | passiveDofsNames | ||
) | |||
raises | ( | Error | |
) |
Add the numerical constraints for path to a node.
nodeId | ID of the node. |
constraintNames | is an array of names of constraints in the ProblemSolver map. |
passiveDofsNames | array of names of vector of passive dofs in the ProblemSolver map. |
intSeq hpp::corbaserver::manipulation::Graph::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 | ||
) | |||
raises | ( | Error | |
) |
Automatically build a constraint graph.
graphName | name of the graph, |
grippers | list of gripper names, |
objects | list of object names, |
handlesPerObject | list of lists of handles, one list per object |
contactsPerObject | list of lists of contact surfaces, one list per object |
envNames | list of names of contact surfaces in the environment, |
list | of rules. |
long hpp::corbaserver::manipulation::Graph::createEdge | ( | in long | nodeFromId, |
in long | nodeToId, | ||
in string | edgeName, | ||
in long | weight, | ||
in long | isInNodeId | ||
) | |||
raises | ( | Error | |
) |
Add an edge between two nodes of the graph.
nodeFromId,nodeToId | the ID of the ends of the new edge. |
edgeName | name of the new edge. |
weight | weight of the edge. |
isInNodeId | id of the node in which paths of the edge are included. |
Referenced by manipulation.constraint_graph.ConstraintGraph::createWaypointEdge().
long hpp::corbaserver::manipulation::Graph::createGraph | ( | in string | graphName | ) | |
raises | ( | Error | |||
) |
Initialize the graph of constraints and add it to the ProblemSolver map.
long hpp::corbaserver::manipulation::Graph::createLevelSetEdge | ( | in long | nodeFromId, |
in long | nodeToId, | ||
in string | edgeName, | ||
in long | weight, | ||
in ID | isInNodeId | ||
) | |||
raises | ( | Error | |
) |
Add an edge of type LevelSetEdge between two nodes.
nodeFromId,nodeToId | the ID of the ends of the new edge. |
edgeName | name of the new edge. |
weight | weight of the edge. |
isInNodeId | id of the node in which paths of the edge are included. |
long hpp::corbaserver::manipulation::Graph::createNode | ( | in long | subGraphId, |
in string | nodeName, | ||
in boolean | waypoint, | ||
in long | priority | ||
) | |||
raises | ( | Error | |
) |
Add a node to the graph.
subGraphId | is the ID of the subgraph to which the node should be added. |
nodeName | the name of the new node. |
waypoint | true when the node is a waypoint |
priority | integer used to order the states. If two states have the same priority, then the order is the order of creation. |
long hpp::corbaserver::manipulation::Graph::createSubGraph | ( | in string | subgraphName | ) | |
raises | ( | Error | |||
) |
Create a subgraph of the constraint graph for one particular end-effector.
long hpp::corbaserver::manipulation::Graph::createWaypointEdge | ( | in long | nodeFromId, |
in long | nodeToId, | ||
in string | edgeName, | ||
in long | number, | ||
in long | weight, | ||
in long | isInNode | ||
) | |||
raises | ( | Error | |
) |
Add an edge with waypoint between two nodes of the graph.
nodeFromId,nodeToId | the ID of the ends of the new edge. |
edgeBaseName | basename of the new edge. |
weight | weight of the edge. |
void hpp::corbaserver::manipulation::Graph::deleteGraph | ( | in string | graphName | ) | |
raises | ( | Error | |||
) |
void hpp::corbaserver::manipulation::Graph::display | ( | in string | filename | ) | |
raises | ( | Error | |||
) |
void hpp::corbaserver::manipulation::Graph::displayEdgeConstraints | ( | in ID | edgeId, |
out string | constraints | ||
) | |||
raises | ( | Error | |
) |
Print set of constraints relative to an edge in a string.
config | Configuration, |
edgeId | id of the edge. |
void hpp::corbaserver::manipulation::Graph::displayEdgeTargetConstraints | ( | in ID | edgeId, |
out string | constraints | ||
) | |||
raises | ( | Error | |
) |
Print set of constraints relative to an edge in a string.
config | Configuration, |
edgeId | id of the edge. |
void hpp::corbaserver::manipulation::Graph::displayNodeConstraints | ( | in ID | nodeId, |
out string | constraints | ||
) | |||
raises | ( | Error | |
) |
Print set of constraints relative to a node in a string.
config | Configuration, |
nodeId | id of the node. |
boolean hpp::corbaserver::manipulation::Graph::getConfigErrorForEdge | ( | in ID | EdgeId, |
in floatSeq | config, | ||
out floatSeq | errorVector | ||
) | |||
raises | ( | Error | |
) |
Get error of a config with respect to an edge constraint.
edgeId | id of the edge. |
config | Configuration, |
error | the error of the edge constraint for the configuration |
boolean hpp::corbaserver::manipulation::Graph::getConfigErrorForEdgeLeaf | ( | in ID | EdgeId, |
in floatSeq | leafConfig, | ||
in floatSeq | config, | ||
out floatSeq | errorVector | ||
) | |||
raises | ( | Error | |
) |
Get error of a config with respect to an edge foliation leaf.
edgeId | id of the edge. |
leafConfig | Configuration that determines the foliation leaf, |
config | Configuration the error of which is computed |
error | the error |
boolean hpp::corbaserver::manipulation::Graph::getConfigErrorForEdgeTarget | ( | in ID | EdgeId, |
in floatSeq | leafConfig, | ||
in floatSeq | config, | ||
out floatSeq | errorVector | ||
) | |||
raises | ( | Error | |
) |
Get error of a config with respect to the target of an edge foliation leaf.
edgeId | id of the edge. |
leafConfig | Configuration that determines the foliation leaf, |
config | Configuration the error of which is computed |
error | the error |
boolean hpp::corbaserver::manipulation::Graph::getConfigErrorForNode | ( | in ID | nodeId, |
in floatSeq | config, | ||
out floatSeq | errorVector | ||
) | |||
raises | ( | Error | |
) |
Get error of a config with respect to a node constraint.
nodeId | id of the node. |
config | Configuration, |
error | the error of the node constraint for the configuration |
boolean hpp::corbaserver::manipulation::Graph::getConfigProjectorStats | ( | in ID | elmt, |
out ConfigProjStat | config, | ||
out ConfigProjStat | path | ||
) | |||
raises | ( | Error | |
) |
Get config projector statistics.
output | config, path object containing the number of success and the number of times a config projector has been called. |
Get in which node an edge is.
edgeId | the ID of the edge, |
void hpp::corbaserver::manipulation::Graph::getEdgeStat | ( | in ID | edgeId, |
out Names_t | reasons, | ||
out intSeq | freqs | ||
) | |||
raises | ( | Error | |
) |
long hpp::corbaserver::manipulation::Graph::getFrequencyOfNodeInRoadmap | ( | in ID | nodeId, |
out intSeq | freqPerConnectedComponent | ||
) | |||
raises | ( | Error | |
) |
Get the number of nodes in the roadmap being in the node nodeId of the graph.
void hpp::corbaserver::manipulation::Graph::getGraph | ( | out GraphComp | graph, |
out GraphElements | elmts | ||
) | |||
raises | ( | Error | |
) |
Get full graph.
void hpp::corbaserver::manipulation::Graph::getHistogramValue | ( | in ID | edgeId, |
out floatSeq | freq, | ||
out floatSeqSeq | values | ||
) | |||
raises | ( | Error | |
) |
void hpp::corbaserver::manipulation::Graph::getLockedJoints | ( | in long | graphComponentId, |
out Names_t | constraintNames | ||
) | |||
raises | ( | Error | |
) |
Get the list of locked joints in a component.
graphComponentId | Id of the component. |
void hpp::corbaserver::manipulation::Graph::getNode | ( | in floatSeq | dofArray, |
out ID | nodeId | ||
) | |||
raises | ( | Error | |
) |
Get the node corresponding to the state of the configuration.
dofArray | the configuration. |
void hpp::corbaserver::manipulation::Graph::getNodesConnectedByEdge | ( | in ID | edgeId, |
out string | from, | ||
out string | to | ||
) | |||
raises | ( | Error | |
) |
Get nodes connected by an edge.
edgeId | id of the edge |
from | name of the node the edge starts from, |
to | name of the node the edge finishes in. |
void hpp::corbaserver::manipulation::Graph::getNumericalConstraints | ( | in long | graphComponentId, |
out Names_t | constraintNames | ||
) | |||
raises | ( | Error | |
) |
Get the list of numerical constraints applied to a component.
graphComponentId | Id of the component. |
void hpp::corbaserver::manipulation::Graph::getRelativeMotionMatrix | ( | in ID | edgeID, |
out intSeqSeq | matrix | ||
) | |||
raises | ( | Error | |
) |
long hpp::corbaserver::manipulation::Graph::getWaypoint | ( | in long | edgeId, |
in long | index, | ||
out ID | nodeId | ||
) | |||
raises | ( | Error | |
) |
Get waypoint IDs of an edge.
edgeId | the ID of the edge. |
index | index of the waypoint. |
void hpp::corbaserver::manipulation::Graph::initialize | ( | ) | ||
raises | ( | Error | ||
) |
This must be called when the graph has been built.
void hpp::corbaserver::manipulation::Graph::removeCollisionPairFromEdge | ( | in ID | edgeId, |
in string | joint1, | ||
in string | joint2 | ||
) | |||
raises | ( | Error | |
) |
Remove collision pairs from an edge.
edgeId | id of the edge, |
joint1,joint2,names | of the joints defining the pair. |
void hpp::corbaserver::manipulation::Graph::resetConstraints | ( | in long | graphComponentId | ) | |
raises | ( | Error | |||
) |
Reset the numerical constraints and the locked joints of a component.
graphComponentId | ID of the component. |
void hpp::corbaserver::manipulation::Graph::selectGraph | ( | in string | graphName | ) | |
raises | ( | Error | |||
) |
Select the graph of contraints from the ProblemSolver map.
void hpp::corbaserver::manipulation::Graph::setContainingNode | ( | in ID | edgeId, |
in ID | nodeId | ||
) | |||
raises | ( | Error | |
) |
Set in which node an edge is.
edgeId | the ID of the edge, |
nodeId | the ID of the node in which the edge is. |
void hpp::corbaserver::manipulation::Graph::setLevelSetFoliation | ( | in long | edgeId, |
in Names_t | condNC, | ||
in Names_t | condLJ, | ||
in Names_t | paramNC, | ||
in Names_t | paramPassiveJoints, | ||
in Names_t | paramLJ | ||
) | |||
raises | ( | Error | |
) |
void hpp::corbaserver::manipulation::Graph::setLockedDofConstraints | ( | in long | graphComponentId, |
in Names_t | constraintNames | ||
) | |||
raises | ( | Error | |
) |
void hpp::corbaserver::manipulation::Graph::setNumericalConstraints | ( | in long | graphComponentId, |
in Names_t | constraintNames, | ||
in Names_t | passiveDofsNames | ||
) | |||
raises | ( | Error | |
) |
void hpp::corbaserver::manipulation::Graph::setNumericalConstraintsForPath | ( | in long | nodeId, |
in Names_t | constraintNames, | ||
in Names_t | passiveDofsNames | ||
) | |||
raises | ( | Error | |
) |
void hpp::corbaserver::manipulation::Graph::setShort | ( | in ID | edgeId, |
in boolean | isShort | ||
) | |||
raises | ( | Error | |
) |
void hpp::corbaserver::manipulation::Graph::setTargetNodeList | ( | in ID | subgraph, |
in IDseq | nodes | ||
) | |||
raises | ( | Error | |
) |
void hpp::corbaserver::manipulation::Graph::setWaypoint | ( | in ID | waypointEdgeId, |
in long | index, | ||
in ID | edgeId, | ||
in ID | nodeId | ||
) | |||
raises | ( | Error | |
) |