hpp::corbaserver::manipulation::Graph Interface Reference

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)
 

Member Function Documentation

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.

Parameters
edgeIdif of a LevelSetEdge of the graph.
condNC,condLJnumerical constraints and locked joints that define the foliated manifold
paramNC,paramPassiveJoints,paramLJnumerical constraints and locked joints that parametrize the foliation
Note
If passiveDofsNames is a shorter list than constraintNames, passiveDofsNames is extended with an empty string, which corresponds to an empty vector of passive dofs.

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.

Parameters
graphComponentIdID of the component.
constraintNamesis 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.

Parameters
graphComponentIdID of the component.
constraintNamesis an array of names of constraints in the ProblemSolver map.
passiveDofsNamesarray of names of vector of passive dofs in the ProblemSolver map.
Note
If passiveDofsNames is a shorter list than constraintNames, passiveDofsNames is extended with an empty string, which corresponds to an empty vector of passive dofs.
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.

Parameters
nodeIdID of the node.
constraintNamesis an array of names of constraints in the ProblemSolver map.
passiveDofsNamesarray of names of vector of passive dofs in the ProblemSolver map.
Note
If passiveDofsNames is a shorter list than constraintNames, passiveDofsNames is extended with an empty string, which corresponds to an empty vector of passive dofs.
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.

Parameters
graphNamename of the graph,
gripperslist of gripper names,
objectslist of object names,
handlesPerObjectlist of lists of handles, one list per object
contactsPerObjectlist of lists of contact surfaces, one list per object
envNameslist of names of contact surfaces in the environment,
listof rules.
Note
We consider a robot with two grippers, three objects with respectively two, one and one handles, and respectively one, two and one contact surface.
grippers = ['gripper_1', 'gripper_2']
objects = ['object_1', 'object_2', 'object_3']
handlesPerObject = [['object_1/handle_1','object_1/handle_2',],
['object_2/handle_1',], ['object_3/handle_1',]]
contactsPerObject = [['object_1/contact_1',],
['object_2/contact_1','object_2/contact_2',],
['object_3/contact_1',]]
from hpp.corbaserver.manipulation import Rule
rules = [Rule(['gripper_1'], ['object_1/handle_2'], True),
Rule(['gripper_1'], ['object_3/handle_1'], True),]
Note
In the rules, gripper and handle names are treated as regular expressions as defined in http://www.boost.org/doc/libs/1_58_0/libs/regex/doc/html/boost_regex/syntax/basic_syntax.html . Pay attention to the version of boost you use.
When creating placement constraints for object "foo", if a constraint with name "place_foo" already exists, the constraint will be used as placement constraint. In this case, if defined, constraint "preplace_foo" will be used as preplacement constraint, if not defined, no preplacement waypoint will be inserted in the graph. If constraint "place_foo" is not defined, it will be created with selected environment and object contact surface.
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.

Parameters
nodeFromId,nodeToIdthe ID of the ends of the new edge.
edgeNamename of the new edge.
weightweight of the edge.
isInNodeIdid 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.

Note
The composite hpp::manipulation::robot must be completely defined first.
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.

Parameters
nodeFromId,nodeToIdthe ID of the ends of the new edge.
edgeNamename of the new edge.
weightweight of the edge.
isInNodeIdid 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.

Parameters
subGraphIdis the ID of the subgraph to which the node should be added.
nodeNamethe name of the new node.
waypointtrue when the node is a waypoint
priorityinteger 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.

Parameters
nodeFromId,nodeToIdthe ID of the ends of the new edge.
edgeBaseNamebasename of the new edge.
weightweight 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.

Parameters
configConfiguration,
edgeIdid of the edge.
Returns
string displaying path constraints 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.

Parameters
configConfiguration,
edgeIdid of the edge.
Returns
string displaying constraints of the edge and of the target node
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.

Parameters
configConfiguration,
nodeIdid of the node.
Returns
string displaying constraints
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.

Parameters
edgeIdid of the edge.
configConfiguration,
Return values
errorthe error of the edge constraint for the configuration
Returns
whether the configuration can be the start point of a path of the edge. Call methods core::ConfigProjector::rightHandSideFromConfig with the input configuration and then core::ConstraintSet::isSatisfied on the edge constraints.
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.

Parameters
edgeIdid of the edge.
leafConfigConfiguration that determines the foliation leaf,
configConfiguration the error of which is computed
Return values
errorthe error
Returns
whether config can be the end point of a path of the edge starting at leafConfig Call methods core::ConfigProjector::rightHandSideFromConfig with leafConfig and then core::ConstraintSet::isSatisfied with config. on the edge constraints.
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.

Parameters
edgeIdid of the edge.
leafConfigConfiguration that determines the foliation leaf,
configConfiguration the error of which is computed
Return values
errorthe error
Returns
whether config can be the end point of a path of the edge starting at leafConfig Call methods core::ConfigProjector::rightHandSideFromConfig with leafConfig and then core::ConstraintSet::isSatisfied with config. on the edge constraints.
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.

Parameters
nodeIdid of the node.
configConfiguration,
Return values
errorthe error of the node constraint for the configuration
Returns
whether the configuration belongs to the node. Call method core::ConstraintSet::isSatisfied for the node constraints.
boolean hpp::corbaserver::manipulation::Graph::getConfigProjectorStats ( in ID  elmt,
out ConfigProjStat  config,
out ConfigProjStat  path 
)
raises (Error
)

Get config projector statistics.

Parameters
outputconfig, path object containing the number of success and the number of times a config projector has been called.
Returns
true if the given has a config projector, false otherwise
string hpp::corbaserver::manipulation::Graph::getContainingNode ( in ID  edgeId)
raises (Error
)

Get in which node an edge is.

Parameters
edgeIdthe ID of the edge,
Returns
the name of the containing node.
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.

Returns
freqPerConnectedComponent is a vector of same number, by connected components.
Warning
The connected components of the roadmap are in no specific order.
void hpp::corbaserver::manipulation::Graph::getGraph ( out GraphComp  graph,
out GraphElements  elmts 
)
raises (Error
)

Get full graph.

Returns
a structure with all the IDs and names
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.

Parameters
graphComponentIdId of the component.
Returns
the list of joints name.
string hpp::corbaserver::manipulation::Graph::getName ( in ID  elmtID)
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.

Parameters
dofArraythe configuration.
Returns
the ID corresponding to the node.
void hpp::corbaserver::manipulation::Graph::getNodesConnectedByEdge ( in ID  edgeId,
out string  from,
out string  to 
)
raises (Error
)

Get nodes connected by an edge.

Parameters
edgeIdid of the edge
fromname of the node the edge starts from,
toname 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.

Parameters
graphComponentIdId of the component.
Returns
the list of constraints name.
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.

Parameters
edgeIdthe ID of the edge.
indexindex of the waypoint.
Returns
the ID of the edge and the node associated with the node.
long hpp::corbaserver::manipulation::Graph::getWeight ( in ID  edgeID)
raises (Error
)
void hpp::corbaserver::manipulation::Graph::initialize ( )
raises (Error
)

This must be called when the graph has been built.

boolean hpp::corbaserver::manipulation::Graph::isShort ( in ID  edgeId)
raises (Error
)
void hpp::corbaserver::manipulation::Graph::removeCollisionPairFromEdge ( in ID  edgeId,
in string  joint1,
in string  joint2 
)
raises (Error
)

Remove collision pairs from an edge.

Parameters
edgeIdid of the edge,
joint1,joint2,namesof 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.

Parameters
graphComponentIdID of the component.
void hpp::corbaserver::manipulation::Graph::selectGraph ( in string  graphName)
raises (Error
)

Select the graph of contraints from the ProblemSolver map.

Note
The composite hpp::manipulation::robot must be completely defined first.
void hpp::corbaserver::manipulation::Graph::setContainingNode ( in ID  edgeId,
in ID  nodeId 
)
raises (Error
)

Set in which node an edge is.

Parameters
edgeIdthe ID of the edge,
nodeIdthe 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
)
Deprecated:
use addLevelSetFoliation
void hpp::corbaserver::manipulation::Graph::setLockedDofConstraints ( in long  graphComponentId,
in Names_t  constraintNames 
)
raises (Error
)
Deprecated:
use addLockedDofConstraints
void hpp::corbaserver::manipulation::Graph::setNumericalConstraints ( in long  graphComponentId,
in Names_t  constraintNames,
in Names_t  passiveDofsNames 
)
raises (Error
)
Deprecated:
use addNumericalConstraints
void hpp::corbaserver::manipulation::Graph::setNumericalConstraintsForPath ( in long  nodeId,
in Names_t  constraintNames,
in Names_t  passiveDofsNames 
)
raises (Error
)
Deprecated:
use addNumericalConstraintsForPath
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
)
void hpp::corbaserver::manipulation::Graph::setWeight ( in ID  edgeID,
in long  weight 
)
raises (Error
)