hpp::manipulation::graph::Graph Class Reference

Description of the constraint graph. More...

#include <hpp/manipulation/graph/graph.hh>

Inheritance diagram for hpp::manipulation::graph::Graph:
[legend]
Collaboration diagram for hpp::manipulation::graph::Graph:
[legend]

Public Member Functions

StateSelectorPtr_t createNodeSelector (const std::string &name) HPP_MANIPULATION_DEPRECATED
 Create and insert a state selector inside the graph. More...
 
StateSelectorPtr_t createStateSelector (const std::string &name)
 Create and insert a state selector inside the graph. More...
 
void nodeSelector (StateSelectorPtr_t ns) HPP_MANIPULATION_DEPRECATED
 Set the state selector. More...
 
void stateSelector (StateSelectorPtr_t ns)
 Set the state selector. More...
 
StateSelectorPtr_t nodeSelector () const HPP_MANIPULATION_DEPRECATED
 Get the state selector. More...
 
StateSelectorPtr_t stateSelector () const
 Get the state selector. More...
 
StatePtr_t getNode (ConfigurationIn_t config) const HPP_MANIPULATION_DEPRECATED
 Returns the states of a configuration. More...
 
StatePtr_t getState (ConfigurationIn_t config) const
 Returns the state of a configuration. More...
 
StatePtr_t getNode (RoadmapNodePtr_t node) const
 Returns the state of a roadmap node. More...
 
StatePtr_t getState (RoadmapNodePtr_t node) const
 Returns the state of a roadmap node. More...
 
Edges_t getEdges (const StatePtr_t &from, const StatePtr_t &to) const
 Get possible edges between two nodes. More...
 
EdgePtr_t chooseEdge (RoadmapNodePtr_t node) const
 Select randomly outgoing edge of the given node. More...
 
void registerConstraints (const ImplicitPtr_t &constraint, const ImplicitPtr_t &complement, const ImplicitPtr_t &both)
 Register a triple of constraints to be inserted in nodes and edges. More...
 
bool isComplement (const ImplicitPtr_t &constraint, const ImplicitPtr_t &complement, ImplicitPtr_t &combinationOfBoth) const
 Test whether two constraints are complement of one another. More...
 
ConstraintSetPtr_t configConstraint (const StatePtr_t &state) const
 Constraint to project onto the Node. More...
 
ConstraintSetPtr_t configConstraint (const EdgePtr_t &edge) const
 Constraint to project onto the same leaf as config. More...
 
bool getConfigErrorForNode (ConfigurationIn_t config, const StatePtr_t &state, vector_t &error) const HPP_MANIPULATION_DEPRECATED
 Get error of a config with respect to a state constraint. More...
 
bool getConfigErrorForState (ConfigurationIn_t config, const StatePtr_t &state, vector_t &error) const
 Get error of a config with respect to a state constraint. More...
 
bool getConfigErrorForEdge (ConfigurationIn_t config, const EdgePtr_t &edge, vector_t &error) const
 Get error of a config with respect to an edge constraint. More...
 
bool getConfigErrorForEdgeLeaf (ConfigurationIn_t leafConfig, ConfigurationIn_t config, const EdgePtr_t &edge, vector_t &error) const
 Get error of a config with respect to an edge foliation leaf. More...
 
bool getConfigErrorForEdgeTarget (ConfigurationIn_t leafConfig, ConfigurationIn_t config, const EdgePtr_t &edge, vector_t &error) const
 Get error of a config with respect to the target of an edge foliation leaf. More...
 
ConstraintSetPtr_t pathConstraint (const EdgePtr_t &edge) const
 Constraint to project a path. More...
 
void maxIterations (size_type iterations)
 Set maximal number of iterations. More...
 
size_type maxIterations () const
 Get maximal number of iterations in config projector. More...
 
void errorThreshold (const value_type &threshold)
 Set error threshold. More...
 
value_type errorThreshold () const
 Get error threshold in config projector. More...
 
const DevicePtr_trobot () const
 Get the robot. More...
 
const ProblemPtr_tproblem () const
 Get the problem. More...
 
void problem (const ProblemPtr_t &problem)
 Set the problem. More...
 
void insertHistogram (const graph::HistogramPtr_t &hist)
 Register an histogram representing a foliation. More...
 
const Histograms_thistograms () const
 Get the histograms. More...
 
GraphComponentWkPtr_t get (std::size_t id) const
 Get the component by its ID. More...
 
std::size_t nbComponents () const
 
virtual std::ostream & dotPrint (std::ostream &os, dot::DrawingAttributes da=dot::DrawingAttributes()) const
 Print the component in DOT language. More...
 
virtual void initialize ()
 
- Public Member Functions inherited from hpp::manipulation::graph::GraphComponent
virtual ~GraphComponent ()
 
const std::string & name () const
 Get the component name. More...
 
const std::size_t & id () const
 Return the component id. More...
 
virtual void addNumericalConstraint (const ImplicitPtr_t &numConstraint, const segments_t &passiveDofs=segments_t())
 Add Implicit to the component. More...
 
virtual void addNumericalConstraint (const DifferentiableFunctionPtr_t &function, const ComparisonTypes_t &ineq) HPP_MANIPULATION_DEPRECATED
 Add core::DifferentiableFunction to the component. More...
 
virtual void resetNumericalConstraints ()
 Reset the numerical constraints stored in the component. More...
 
virtual void addLockedJointConstraint (const LockedJointPtr_t &constraint)
 Add core::LockedJoint constraint to the component. More...
 
virtual void resetLockedJoints ()
 Reset the locked joint in the component. More...
 
bool insertNumericalConstraints (ConfigProjectorPtr_t &proj) const
 Insert the numerical constraints in a ConfigProjector. More...
 
bool insertLockedJoints (ConfigProjectorPtr_t &cs) const
 Insert the LockedJoint constraints in a ConstraintSet. More...
 
const NumericalConstraints_tnumericalConstraints () const
 Get a reference to the NumericalConstraints_t. More...
 
const IntervalsContainer_tpassiveDofs () const
 Get a reference to the NumericalConstraints_t. More...
 
const LockedJoints_tlockedJoints () const
 Get a reference to the LockedJoints_t. More...
 
void parentGraph (const GraphWkPtr_t &parent)
 Set the parent graph. More...
 
GraphPtr_t parentGraph () const
 Set the parent graph. More...
 
void setDirty ()
 Declare a component as dirty. More...
 

Static Public Member Functions

static GraphPtr_t create (const std::string &name, DevicePtr_t robot, const ProblemPtr_t &problem)
 Create a new Graph. More...
 

Protected Member Functions

void init (const GraphWkPtr_t &weak, DevicePtr_t robot)
 Initialization of the object. More...
 
 Graph (const std::string &name, const ProblemPtr_t &problem)
 Constructor. More...
 
std::ostream & print (std::ostream &os) const
 Print the object in a stream. More...
 
- Protected Member Functions inherited from hpp::manipulation::graph::GraphComponent
void init (const GraphComponentWkPtr_t &weak)
 Initialize the component. More...
 
 GraphComponent (const std::string &name)
 
void throwIfNotInitialized () const
 
virtual void populateTooltip (dot::Tooltip &tp) const
 Populate DrawingAttributes tooltip. More...
 

Friends

class GraphComponent
 

Additional Inherited Members

- Protected Attributes inherited from hpp::manipulation::graph::GraphComponent
NumericalConstraints_t numericalConstraints_
 Stores the numerical constraints. More...
 
IntervalsContainer_t passiveDofs_
 Stores the passive dofs for each numerical constraints. More...
 
LockedJoints_t lockedJoints_
 List of LockedJoint constraints. More...
 
GraphWkPtr_t graph_
 A weak pointer to the parent graph. More...
 
bool isInit_
 

Detailed Description

Description of the constraint graph.

This class contains a graph representing a robot with several end-effectors.

One must make sure not to create loop with shared pointers. To ensure that, the classes are defined as follow:

Constructor & Destructor Documentation

hpp::manipulation::graph::Graph::Graph ( const std::string &  name,
const ProblemPtr_t problem 
)
inlineprotected

Constructor.

Parameters
sma steering method to create paths from edges

References print(), and robot_.

Member Function Documentation

EdgePtr_t hpp::manipulation::graph::Graph::chooseEdge ( RoadmapNodePtr_t  node) const

Select randomly outgoing edge of the given node.

ConstraintSetPtr_t hpp::manipulation::graph::Graph::configConstraint ( const StatePtr_t state) const

Constraint to project onto the Node.

Parameters
statethe state on which to project.
Returns
The initialized projector.
ConstraintSetPtr_t hpp::manipulation::graph::Graph::configConstraint ( const EdgePtr_t edge) const

Constraint to project onto the same leaf as config.

Parameters
edgesa list of edges defining the foliation.
Returns
The constraint.
static GraphPtr_t hpp::manipulation::graph::Graph::create ( const std::string &  name,
DevicePtr_t  robot,
const ProblemPtr_t problem 
)
static

Create a new Graph.

Parameters
robota manipulation robot
problema pointer to the problem
StateSelectorPtr_t hpp::manipulation::graph::Graph::createNodeSelector ( const std::string &  name)

Create and insert a state selector inside the graph.

Deprecated:
use createStateSelector instead
StateSelectorPtr_t hpp::manipulation::graph::Graph::createStateSelector ( const std::string &  name)

Create and insert a state selector inside the graph.

virtual std::ostream& hpp::manipulation::graph::Graph::dotPrint ( std::ostream &  os,
dot::DrawingAttributes  da = dot::DrawingAttributes() 
) const
virtual

Print the component in DOT language.

Reimplemented from hpp::manipulation::graph::GraphComponent.

void hpp::manipulation::graph::Graph::errorThreshold ( const value_type threshold)

Set error threshold.

value_type hpp::manipulation::graph::Graph::errorThreshold ( ) const

Get error threshold in config projector.

GraphComponentWkPtr_t hpp::manipulation::graph::Graph::get ( std::size_t  id) const

Get the component by its ID.

bool hpp::manipulation::graph::Graph::getConfigErrorForEdge ( ConfigurationIn_t  config,
const EdgePtr_t edge,
vector_t error 
) const

Get error of a config with respect to an edge constraint.

Parameters
configConfiguration,
edgeedge containing the constraint to check config against
Return values
errorthe error of the edge constraint for the configuration
Returns
whether the configuration can be a start point of a path Call core::ConfigProjector::rightHandSideFromConfig with input configuration and method core::ConstraintSet::isSatisfied for the edge constraint.
bool hpp::manipulation::graph::Graph::getConfigErrorForEdgeLeaf ( ConfigurationIn_t  leafConfig,
ConfigurationIn_t  config,
const EdgePtr_t edge,
vector_t error 
) const

Get error of a config with respect to an edge foliation leaf.

Parameters
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.
bool hpp::manipulation::graph::Graph::getConfigErrorForEdgeTarget ( ConfigurationIn_t  leafConfig,
ConfigurationIn_t  config,
const EdgePtr_t edge,
vector_t error 
) const

Get error of a config with respect to the target of an edge foliation leaf.

Parameters
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.
bool hpp::manipulation::graph::Graph::getConfigErrorForNode ( ConfigurationIn_t  config,
const StatePtr_t state,
vector_t error 
) const

Get error of a config with respect to a state constraint.

Parameters
configConfiguration,
statestate containing the constraint to check config against
Return values
errorthe error of the state constraint for the configuration
Returns
whether the configuration belongs to the state. Call method core::ConstraintSet::isSatisfied for the state constraints.
Deprecated:
use getConfigErrorForState instead
bool hpp::manipulation::graph::Graph::getConfigErrorForState ( ConfigurationIn_t  config,
const StatePtr_t state,
vector_t error 
) const

Get error of a config with respect to a state constraint.

Parameters
configConfiguration,
statestate containing the constraint to check config against
Return values
errorthe error of the state constraint for the configuration
Returns
whether the configuration belongs to the state. Call method core::ConstraintSet::isSatisfied for the state constraints.
Edges_t hpp::manipulation::graph::Graph::getEdges ( const StatePtr_t from,
const StatePtr_t to 
) const

Get possible edges between two nodes.

StatePtr_t hpp::manipulation::graph::Graph::getNode ( ConfigurationIn_t  config) const

Returns the states of a configuration.

Deprecated:
use getState instead
StatePtr_t hpp::manipulation::graph::Graph::getNode ( RoadmapNodePtr_t  node) const

Returns the state of a roadmap node.

Deprecated:
use getState instead
StatePtr_t hpp::manipulation::graph::Graph::getState ( ConfigurationIn_t  config) const

Returns the state of a configuration.

StatePtr_t hpp::manipulation::graph::Graph::getState ( RoadmapNodePtr_t  node) const

Returns the state of a roadmap node.

const Histograms_t& hpp::manipulation::graph::Graph::histograms ( ) const
inline

Get the histograms.

void hpp::manipulation::graph::Graph::init ( const GraphWkPtr_t &  weak,
DevicePtr_t  robot 
)
protected

Initialization of the object.

virtual void hpp::manipulation::graph::Graph::initialize ( )
virtual
void hpp::manipulation::graph::Graph::insertHistogram ( const graph::HistogramPtr_t hist)
inline

Register an histogram representing a foliation.

bool hpp::manipulation::graph::Graph::isComplement ( const ImplicitPtr_t constraint,
const ImplicitPtr_t complement,
ImplicitPtr_t combinationOfBoth 
) const

Test whether two constraints are complement of one another.

Parameters
constraint,complementtwo constraints to test
Return values
combinationOfBothconstraint corresponding to combining constraint and complement if result is true, unchanged otherwise.
Returns
whether complement is the complement of constraint. Two constraints are complement of one another if and only if combined they constitute a complement relative transformation constraint.
See also
Graph::registerConstraints
Warning
argument order matters.
void hpp::manipulation::graph::Graph::maxIterations ( size_type  iterations)

Set maximal number of iterations.

size_type hpp::manipulation::graph::Graph::maxIterations ( ) const

Get maximal number of iterations in config projector.

std::size_t hpp::manipulation::graph::Graph::nbComponents ( ) const
inline

References init().

void hpp::manipulation::graph::Graph::nodeSelector ( StateSelectorPtr_t  ns)

Set the state selector.

Warning
This should be done before adding nodes to the node selector otherwise the pointer to the parent graph will NOT be valid.
Deprecated:
use stateSelector instead
StateSelectorPtr_t hpp::manipulation::graph::Graph::nodeSelector ( ) const
inline

Get the state selector.

Deprecated:
use stateSelector instead
ConstraintSetPtr_t hpp::manipulation::graph::Graph::pathConstraint ( const EdgePtr_t edge) const

Constraint to project a path.

Parameters
edgea list of edges defining the foliation.
Returns
The constraint.
std::ostream& hpp::manipulation::graph::Graph::print ( std::ostream &  os) const
protectedvirtual

Print the object in a stream.

Reimplemented from hpp::manipulation::graph::GraphComponent.

const ProblemPtr_t& hpp::manipulation::graph::Graph::problem ( ) const

Get the problem.

void hpp::manipulation::graph::Graph::problem ( const ProblemPtr_t problem)

Set the problem.

void hpp::manipulation::graph::Graph::registerConstraints ( const ImplicitPtr_t constraint,
const ImplicitPtr_t complement,
const ImplicitPtr_t both 
)

Register a triple of constraints to be inserted in nodes and edges.

Parameters
constrainta constraint (grasp of placement)
complementthe complement constraint
bothcombination of the constraint and its complement. Both constraints together corresponds to a full relative transformation constraint When inserting constraints in transitions of the graph, in many cases, a constraint is associated to a state and the complement constraint is associated to the transition itself. Registering those constraints priorly to graph construction makes possible to replace the constraint and its complement by the combination of both that is an explicit constraint.
const DevicePtr_t& hpp::manipulation::graph::Graph::robot ( ) const

Get the robot.

void hpp::manipulation::graph::Graph::stateSelector ( StateSelectorPtr_t  ns)

Set the state selector.

Warning
This should be done before adding nodes to the node selector otherwise the pointer to the parent graph will NOT be valid.
StateSelectorPtr_t hpp::manipulation::graph::Graph::stateSelector ( ) const
inline

Get the state selector.

References problem().

Friends And Related Function Documentation

friend class GraphComponent
friend