pose_graph::ConstraintGraph Class Reference

#include <constraint_graph.h>

List of all members.

Public Member Functions

void addEdge (unsigned id, unsigned from, unsigned t, const PoseWithPrecision &constraint)
 Add a new edge with the given id.
unsigned addEdge (unsigned from, unsigned t, const PoseWithPrecision &constraint)
 Add a new edge and return its id.
void addNode (unsigned id)
 Add a new node with a given id.
unsigned addNode ()
 Add a new node, and return its id, which is > 0.
EdgeSet allEdges () const
 Get set of edge ids.
NodeSet allNodes () const
 Get set of node ids.
 ConstraintGraph (const ConstraintGraph &g)
 Copy constructor.
 ConstraintGraph ()
 Create empty graph.
bool edgeIdExists (unsigned e) const
const PoseWithPrecision & getConstraint (unsigned e) const
 Get constraint attached to this edge.
tf::Pose getOptimizedPose (unsigned n) const
 Get optimized pose of a node, if it exists.
const Graphgraph () const
 Return (a const reference to) the underlying Boost graph.
bool hasOptimizedPose (unsigned n) const
GraphEdge idEdge (unsigned e) const
 Get the edge handle given an id.
GraphVertex idVertex (unsigned n) const
 Get the node handle given an id.
EdgeSet incidentEdges (unsigned n) const
 Get set of edges incident to a node.
std::pair< unsigned, unsigned > incidentNodes (unsigned e) const
 Get pair of nodes adjacent to this edge, in order (src, dest).
bool nodeIdExists (unsigned n) const
virtual ConstraintGraphoperator= (const ConstraintGraph &g)
 Assignment operator.
void setOptimizedPose (unsigned n, const tf::Pose &pose)
 Set optimized pose in graph.
void setOptimizedPoses (const NodePoseMap &poses)
 Replace the set of optimized poses currently stored in graph with new ones.
virtual ~ConstraintGraph ()
 Destructor.

Private Member Functions

void initializeFrom (const ConstraintGraph &other)

Private Attributes

std::map< unsigned, GraphEdgeedge_map_
Graph graph_
unsigned next_edge_id_
unsigned next_node_id_
std::map< unsigned, GraphVertexvertex_map_

Detailed Description

Definition at line 90 of file constraint_graph.h.


Constructor & Destructor Documentation

pose_graph::ConstraintGraph::ConstraintGraph (  ) 

Create empty graph.

Definition at line 58 of file constraint_graph.cpp.

pose_graph::ConstraintGraph::ConstraintGraph ( const ConstraintGraph g  ) 

Copy constructor.

Definition at line 65 of file constraint_graph.cpp.

pose_graph::ConstraintGraph::~ConstraintGraph (  )  [virtual]

Destructor.

Definition at line 62 of file constraint_graph.cpp.


Member Function Documentation

void pose_graph::ConstraintGraph::addEdge ( unsigned  id,
unsigned  from,
unsigned  t,
const PoseWithPrecision &  constraint 
)

Add a new edge with the given id.

Exceptions:
DuplicateEdgeIdException if already exists

Definition at line 137 of file constraint_graph.cpp.

unsigned pose_graph::ConstraintGraph::addEdge ( unsigned  from,
unsigned  t,
const PoseWithPrecision &  constraint 
)

Add a new edge and return its id.

Definition at line 128 of file constraint_graph.cpp.

void pose_graph::ConstraintGraph::addNode ( unsigned  id  ) 

Add a new node with a given id.

Exceptions:
DuplicateNodeIdException if already exists

Definition at line 119 of file constraint_graph.cpp.

unsigned pose_graph::ConstraintGraph::addNode (  ) 

Add a new node, and return its id, which is > 0.

Definition at line 111 of file constraint_graph.cpp.

EdgeSet pose_graph::ConstraintGraph::allEdges (  )  const

Get set of edge ids.

Definition at line 163 of file constraint_graph.cpp.

NodeSet pose_graph::ConstraintGraph::allNodes (  )  const

Get set of node ids.

Definition at line 155 of file constraint_graph.cpp.

bool pose_graph::ConstraintGraph::edgeIdExists ( unsigned  e  )  const
Return values:
Does an edge with this id exist?

Definition at line 277 of file constraint_graph.cpp.

const PoseWithPrecision & pose_graph::ConstraintGraph::getConstraint ( unsigned  e  )  const

Get constraint attached to this edge.

Note:
Returned value may change; make a copy if necessary

Definition at line 198 of file constraint_graph.cpp.

tf::Pose pose_graph::ConstraintGraph::getOptimizedPose ( unsigned  n  )  const

Get optimized pose of a node, if it exists.

Exceptions:
UnknownNodeIdException 
NoOptimizedPoseExecption 

Definition at line 232 of file constraint_graph.cpp.

const Graph & pose_graph::ConstraintGraph::graph (  )  const

Return (a const reference to) the underlying Boost graph.

To get convert ids into edge/vertex handles for use with the returned object, use idVertex and idEdge

Definition at line 207 of file constraint_graph.cpp.

bool pose_graph::ConstraintGraph::hasOptimizedPose ( unsigned  n  )  const

Does this node have an optimized pose?

Exceptions:
UnknownIdException 

Definition at line 263 of file constraint_graph.cpp.

GraphEdge pose_graph::ConstraintGraph::idEdge ( unsigned  e  )  const

Get the edge handle given an id.

Definition at line 212 of file constraint_graph.cpp.

GraphVertex pose_graph::ConstraintGraph::idVertex ( unsigned  n  )  const

Get the node handle given an id.

Exceptions:
UnknownNodeIdException 

Definition at line 220 of file constraint_graph.cpp.

EdgeSet pose_graph::ConstraintGraph::incidentEdges ( unsigned  n  )  const

Get set of edges incident to a node.

Note:
Returned value may change; make a copy if necessary

Definition at line 172 of file constraint_graph.cpp.

IncidentNodes pose_graph::ConstraintGraph::incidentNodes ( unsigned  e  )  const

Get pair of nodes adjacent to this edge, in order (src, dest).

Exceptions:
UnknownEdgeIdException 

Definition at line 181 of file constraint_graph.cpp.

void pose_graph::ConstraintGraph::initializeFrom ( const ConstraintGraph other  )  [private]

Clear out data associated with old graph

Definition at line 79 of file constraint_graph.cpp.

bool pose_graph::ConstraintGraph::nodeIdExists ( unsigned  n  )  const
Return values:
Does a node with this id exist?

Definition at line 272 of file constraint_graph.cpp.

ConstraintGraph & pose_graph::ConstraintGraph::operator= ( const ConstraintGraph g  )  [virtual]

Assignment operator.

Definition at line 71 of file constraint_graph.cpp.

void pose_graph::ConstraintGraph::setOptimizedPose ( unsigned  n,
const tf::Pose &  pose 
)

Set optimized pose in graph.

Exceptions:
UnknownNodeIdException 
Note:
It's the caller's responsibility to ensure that the pose being set here is consistent with all the poses already in the graph; if not, use setOptimizedPoses

Definition at line 242 of file constraint_graph.cpp.

void pose_graph::ConstraintGraph::setOptimizedPoses ( const NodePoseMap poses  ) 

Replace the set of optimized poses currently stored in graph with new ones.

Exceptions:
UnknownNodeIdException 

Definition at line 249 of file constraint_graph.cpp.


Member Data Documentation

std::map<unsigned, GraphEdge> pose_graph::ConstraintGraph::edge_map_ [private]

Definition at line 209 of file constraint_graph.h.

Definition at line 210 of file constraint_graph.h.

Definition at line 207 of file constraint_graph.h.

Definition at line 206 of file constraint_graph.h.

Definition at line 208 of file constraint_graph.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Defines


pose_graph
Author(s): Bhaskara Marthi
autogenerated on Fri Jan 11 09:37:08 2013