hpp-manipulation-corba  4.9.0
Corba server for manipulation planning
hpp::corbaserver::manipulation::Graph Interface Reference

import"/home/florent/devel/release/src/hpp-manipulation-corba/idl/hpp/corbaserver/manipulation/graph.idl";

Public Member Functions

long createGraph (in string graphName) raises (Error)
 
void deleteGraph (in string graphName) raises (Error)
 
void selectGraph (in string graphName) raises (Error)
 
void createSubGraph (in string subgraphName) raises (Error)
 Create a subgraph of the constraint graph for one particular end-effector. More...
 
void setTargetNodeList (in ID graphId, in IDseq nodes) raises (Error)
 
long createNode (in long graphId, in string nodeName, in boolean waypoint, in long priority) raises (Error)
 
long createEdge (in long nodeFromId, in long nodeToId, in string edgeName, in long weight, in long isInNodeId) raises (Error)
 
void setContainingNode (in ID edgeId, in ID nodeId) raises (Error)
 
string getContainingNode (in ID edgeId) raises (Error)
 
long createWaypointEdge (in long nodeFromId, in long nodeToId, in string edgeName, in long number, in long weight, in long isInNode) raises (Error)
 
long getWaypoint (in long edgeId, in long index, out ID nodeId) raises (Error)
 
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)
 
void getEdgeStat (in ID edgeId, out Names_t reasons, out intSeq freqs) raises (Error)
 
long getFrequencyOfNodeInRoadmap (in ID nodeId, out intSeq freqPerConnectedComponent) raises (Error)
 
boolean getConfigProjectorStats (in ID elmt, out ConfigProjStat config, out ConfigProjStat path) raises (Error)
 
long createLevelSetEdge (in long nodeFromId, in long nodeToId, in string edgeName, in long weight, in ID isInNodeId) raises (Error)
 
void addLevelSetFoliation (in long edgeId, in Names_t condNC, in Names_t paramNC) raises (Error)
 
void resetConstraints (in long graphComponentId) raises (Error)
 
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)
 
void getNumericalConstraints (in long graphComponentId, out Names_t constraintNames) raises (Error)
 
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)
 
void removeCollisionPairFromEdge (in ID edgeId, in string joint1, in string joint2) raises (Error)
 
void getNode (in floatSeq dofArray, out ID nodeId) raises (Error)
 
boolean applyNodeConstraints (in ID idComp, in floatSeq input, out floatSeq output, out double residualError) raises (Error)
 
boolean applyEdgeLeafConstraints (in ID idedge, in floatSeq qleaf, in floatSeq input, out floatSeq output, out double residualError) raises (Error)
 
boolean generateTargetConfig (in ID IDedge, in floatSeq qleaf, in floatSeq input, out floatSeq output, out double residualError) raises (Error)
 
boolean getConfigErrorForNode (in ID nodeId, in floatSeq config, out floatSeq errorVector) raises (Error)
 
boolean getConfigErrorForEdge (in ID EdgeId, in floatSeq config, out floatSeq errorVector) raises (Error)
 
boolean getConfigErrorForEdgeLeaf (in ID EdgeId, in floatSeq leafConfig, in floatSeq config, out floatSeq errorVector) raises (Error)
 
boolean getConfigErrorForEdgeTarget (in ID EdgeId, in floatSeq leafConfig, in floatSeq config, out floatSeq errorVector) raises (Error)
 
void displayNodeConstraints (in ID nodeId, out string constraints) raises (Error)
 
void displayEdgeTargetConstraints (in ID edgeId, out string constraints) raises (Error)
 
void displayEdgeConstraints (in ID edgeId, out string constraints) raises (Error)
 
void getNodesConnectedByEdge (in ID edgeId, out string from, out string to) raises (Error)
 
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)
 
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) raises (Error)
 
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 setSecurityMarginForEdge (in ID edgeID, in string joint1, in string joint2, in double margin) raises (Error)
 

Member Function Documentation

◆ addLevelSetFoliation()

void hpp::corbaserver::manipulation::Graph::addLevelSetFoliation ( in long  edgeId,
in Names_t  condNC,
in Names_t  paramNC 
)
raises (Error
)

Add the constraints to a LevelSetEdge that create the foliation.

Parameters
edgeIdif of a LevelSetEdge of the graph.
condNCnumerical constraints that define the foliated manifold
paramNCnumerical constraints that parameterize the foliation

◆ addNumericalConstraints()

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.

◆ addNumericalConstraintsForPath()

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.

◆ applyEdgeLeafConstraints()

boolean hpp::corbaserver::manipulation::Graph::applyEdgeLeafConstraints ( in ID  idedge,
in floatSeq  qleaf,
in floatSeq  input,
out floatSeq  output,
out double  residualError 
)
raises (Error
)

Apply constraints of an edge leaf to a configuration

Parameters
idIDedge of the edge
qleafConfiguration defining the leaf
inputinput configuration to be projected
Return values
outputOutput configuration,
residualErrornorm of the residual error

◆ applyNodeConstraints()

boolean hpp::corbaserver::manipulation::Graph::applyNodeConstraints ( in ID  idComp,
in floatSeq  input,
out floatSeq  output,
out double  residualError 
)
raises (Error
)

Apply constaints of a state to a configuration

Parameters
idCompID of a state (node of the constraint graph)
inputinput configuration,
Return values
outputoutput configuration,
errornorm of the residual error.

◆ autoBuild()

long 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.

◆ createEdge()

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.

◆ createGraph()

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.

◆ createLevelSetEdge()

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.

◆ createNode()

long hpp::corbaserver::manipulation::Graph::createNode ( in long  graphId,
in string  nodeName,
in boolean  waypoint,
in long  priority 
)
raises (Error
)

Add a node to the graph.

Parameters
graphIdis the ID of the graph 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.

◆ createSubGraph()

void hpp::corbaserver::manipulation::Graph::createSubGraph ( in string  subgraphName)
raises (Error
)

Create a subgraph of the constraint graph for one particular end-effector.

◆ createWaypointEdge()

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.

◆ deleteGraph()

void hpp::corbaserver::manipulation::Graph::deleteGraph ( in string  graphName)
raises (Error
)

◆ display()

void hpp::corbaserver::manipulation::Graph::display ( in string  filename)
raises (Error
)

◆ displayEdgeConstraints()

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

◆ displayEdgeTargetConstraints()

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

◆ displayNodeConstraints()

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

◆ generateTargetConfig()

boolean hpp::corbaserver::manipulation::Graph::generateTargetConfig ( in ID  IDedge,
in floatSeq  qleaf,
in floatSeq  input,
out floatSeq  output,
out double  residualError 
)
raises (Error
)

Generate configuration in target state of a transition reachable from a configuration

Parameters
IDedgeID of a transition (edge of the constraint graph)
qleafconfiguration defining the leaf of the transition
inputinput configuration to be projected
Return values
outputoutput configuration,
residualErrornorm of the residual error.

◆ getConfigErrorForEdge()

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.

◆ getConfigErrorForEdgeLeaf()

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.

◆ getConfigErrorForEdgeTarget()

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.

◆ getConfigErrorForNode()

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.

◆ getConfigProjectorStats()

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

◆ getContainingNode()

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.

◆ getEdgeStat()

void hpp::corbaserver::manipulation::Graph::getEdgeStat ( in ID  edgeId,
out Names_t  reasons,
out intSeq  freqs 
)
raises (Error
)

◆ getFrequencyOfNodeInRoadmap()

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.

◆ getGraph()

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

◆ getHistogramValue()

void hpp::corbaserver::manipulation::Graph::getHistogramValue ( in ID  edgeId,
out floatSeq  freq,
out floatSeqSeq  values 
)
raises (Error
)

◆ getName()

string hpp::corbaserver::manipulation::Graph::getName ( in ID  elmtID)
raises (Error
)

Get name of graph component

Parameters
componentindex in the graph
See also
hpp::manipulation::graph::Graph::get

◆ getNode()

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.

◆ getNodesConnectedByEdge()

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.

◆ getNumericalConstraints()

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.

◆ getRelativeMotionMatrix()

void hpp::corbaserver::manipulation::Graph::getRelativeMotionMatrix ( in ID  edgeID,
out intSeqSeq  matrix 
)
raises (Error
)

Get the matrix of relative motions for an edge

Parameters
edgeIdindex of the edge,
Return values
matrixas defined in hpp::core::RelativeMotion::matrix_type.

◆ getWaypoint()

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.

◆ getWeight()

long hpp::corbaserver::manipulation::Graph::getWeight ( in ID  edgeID)
raises (Error
)

Get weight of graph component

Parameters
componentindex in the graph, should be an edge
See also
hpp::manipulation::graph::State::getWeight

◆ initialize()

void hpp::corbaserver::manipulation::Graph::initialize ( )
raises (Error
)

This must be called when the graph has been built.

◆ isShort()

boolean hpp::corbaserver::manipulation::Graph::isShort ( in ID  edgeId)
raises (Error
)

◆ removeCollisionPairFromEdge()

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.

◆ resetConstraints()

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.

◆ selectGraph()

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.

◆ setContainingNode()

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.

◆ setNumericalConstraints()

void hpp::corbaserver::manipulation::Graph::setNumericalConstraints ( in long  graphComponentId,
in Names_t  constraintNames,
in Names_t  passiveDofsNames 
)
raises (Error
)
Deprecated:
use addNumericalConstraints

◆ setNumericalConstraintsForPath()

void hpp::corbaserver::manipulation::Graph::setNumericalConstraintsForPath ( in long  nodeId,
in Names_t  constraintNames,
in Names_t  passiveDofsNames 
)
raises (Error
)
Deprecated:
use addNumericalConstraintsForPath

◆ setSecurityMarginForEdge()

void hpp::corbaserver::manipulation::Graph::setSecurityMarginForEdge ( in ID  edgeID,
in string  joint1,
in string  joint2,
in double  margin 
)
raises (Error
)

Set collision security margin for a pair of joint along an edge

Parameters
edgeIDindex of the edge,
joint1,joint2names of joint1 and joint2
marginsecurity margin for collision tests between those joints along the edge.

◆ setShort()

void hpp::corbaserver::manipulation::Graph::setShort ( in ID  edgeId,
in boolean  isShort 
)
raises (Error
)

◆ setTargetNodeList()

void hpp::corbaserver::manipulation::Graph::setTargetNodeList ( in ID  graphId,
in IDseq  nodes 
)
raises (Error
)

◆ setWaypoint()

void hpp::corbaserver::manipulation::Graph::setWaypoint ( in ID  waypointEdgeId,
in long  index,
in ID  edgeId,
in ID  nodeId 
)
raises (Error
)

◆ setWeight()

void hpp::corbaserver::manipulation::Graph::setWeight ( in ID  edgeID,
in long  weight 
)
raises (Error
)

Set weight of graph component

Parameters
componentindex in the graph, should be an edge
See also
hpp::manipulation::graph::State::setWeight

The documentation for this interface was generated from the following file: