import "/local/robotpkg/var/tmp/robotpkg/path/hpp-manipulation-corba/work/hpp-manipulation-corba-1.1.0/idl/hpp/corbaserver/manipulation/graph.idl";
Public Member Functions | |
long | createGraph (in string graphName) raises (Error) |
Initialize the graph of constraints. | |
long | createSubGraph (in string subgraphName) raises (Error) |
Create a subgraph of the constraint graph for one particular end-effector. | |
long | createNode (in long subGraphId, in string nodeName) raises (Error) |
Add a node to the graph. | |
long | createEdge (in long nodeFromId, in long nodeToId, in string edgeName, in long weight, in boolean isInNodeFrom) raises (Error) |
Add an edge between two nodes of the graph. | |
void | isInNodeFrom (in long edgeId, in boolean isInNodeFrom) raises (Error) |
Set in which node an edge is. | |
void | createWaypointEdge (in long nodeFromId, in long nodeToId, in string edgeName, in long number, in long weight, in boolean isInNodeFrom, out GraphElements elmts) raises (Error) |
Add an edge with waypoint between two nodes of the graph. | |
long | getWaypoint (in long edgeId, out ID nodeId) raises (Error) |
Get waypoint IDs of an edge. | |
long | createLevelSetEdge (in long nodeFromId, in long nodeToId, in string edgeName, in long weight, in boolean isInNodeFrom) raises (Error) |
Add an edge of type LevelSetEdge between two nodes. | |
void | setLevelSetConstraints (in long edgeId, in Names_t numericalConstraintNames, in Names_t passiveDofsNames, in Names_t lockedDofNames) raises (Error) |
Set the numerical constraints of a LevelSetEdge that are create the foliation. | |
void | setNumericalConstraints (in long graphComponentId, in Names_t constraintNames, in Names_t passiveDofsNames) raises (Error) |
Set the numerical constraints of a component. | |
void | setNumericalConstraintsForPath (in long nodeId, in Names_t constraintNames, in Names_t passiveDofsNames) raises (Error) |
Set the numerical constraints for path of a node. | |
void | setLockedDofConstraints (in long graphComponentId, in Names_t constraintNames) raises (Error) |
Set the LockedDof constraints of a component. | |
void | statOnConstraint (in ID IDedge) raises (Error) |
Activate statistic analysis for this sequence of edges. | |
void | getNode (in floatSeq dofArray, out ID nodeId) raises (Error) |
Get the node corresponding to the state of the configuration. | |
void | display (in string filename) raises (Error) |
long hpp::corbaserver::manipulation::Graph::createEdge | ( | in long | nodeFromId, |
in long | nodeToId, | ||
in string | edgeName, | ||
in long | weight, | ||
in boolean | isInNodeFrom | ||
) | 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. |
long hpp::corbaserver::manipulation::Graph::createGraph | ( | in string | graphName | ) | raises (Error) |
Initialize the graph of constraints.
long hpp::corbaserver::manipulation::Graph::createLevelSetEdge | ( | in long | nodeFromId, |
in long | nodeToId, | ||
in string | edgeName, | ||
in long | weight, | ||
in boolean | isInNodeFrom | ||
) | 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. |
long hpp::corbaserver::manipulation::Graph::createNode | ( | in long | subGraphId, |
in string | nodeName | ||
) | 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. |
long hpp::corbaserver::manipulation::Graph::createSubGraph | ( | in string | subgraphName | ) | raises (Error) |
Create a subgraph of the constraint graph for one particular end-effector.
void hpp::corbaserver::manipulation::Graph::createWaypointEdge | ( | in long | nodeFromId, |
in long | nodeToId, | ||
in string | edgeName, | ||
in long | number, | ||
in long | weight, | ||
in boolean | isInNodeFrom, | ||
out GraphElements | elmts | ||
) | 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::display | ( | in string | filename | ) | raises (Error) |
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. |
long hpp::corbaserver::manipulation::Graph::getWaypoint | ( | in long | edgeId, |
out ID | nodeId | ||
) | raises (Error) |
Get waypoint IDs of an edge.
edgeId | the ID of the edge. |
void hpp::corbaserver::manipulation::Graph::isInNodeFrom | ( | in long | edgeId, |
in boolean | isInNodeFrom | ||
) | raises (Error) |
Set in which node an edge is.
edgeId | the ID of the edge, |
isInNodeFrom | whether or not a path corresponding to this edge is in the node from. |
void hpp::corbaserver::manipulation::Graph::setLevelSetConstraints | ( | in long | edgeId, |
in Names_t | numericalConstraintNames, | ||
in Names_t | passiveDofsNames, | ||
in Names_t | lockedDofNames | ||
) | raises (Error) |
Set the numerical constraints of a LevelSetEdge that are create the foliation.
graphComponentId | ID of the component. |
numericalConstraintNames | is an array of names of numerical constraints in the ProblemSolver map. |
lockedDofNames | is an array of names of LockedDof constraints in the ProblemSolver map. |
passiveDofsNames | array of names of vector of passive dofs in the ProblemSolver map. |
void hpp::corbaserver::manipulation::Graph::setLockedDofConstraints | ( | in long | graphComponentId, |
in Names_t | constraintNames | ||
) | raises (Error) |
Set the LockedDof constraints of a component.
graphComponentId | ID of the component. |
constraintNames | is an array of names of constraints in the ProblemSolver map. |
void hpp::corbaserver::manipulation::Graph::setNumericalConstraints | ( | in long | graphComponentId, |
in Names_t | constraintNames, | ||
in Names_t | passiveDofsNames | ||
) | raises (Error) |
Set the numerical constraints of 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::setNumericalConstraintsForPath | ( | in long | nodeId, |
in Names_t | constraintNames, | ||
in Names_t | passiveDofsNames | ||
) | raises (Error) |
Set the numerical constraints for path of 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. |
void hpp::corbaserver::manipulation::Graph::statOnConstraint | ( | in ID | IDedge | ) | raises (Error) |
Activate statistic analysis for this sequence of edges.
IDedge | edge ID. |