Classes | Public Types | Public Member Functions | Protected Attributes
g2o::OptimizableGraph Struct Reference

#include <optimizable_graph.h>

Inheritance diagram for g2o::OptimizableGraph:
Inheritance graph
[legend]

List of all members.

Classes

struct  Data
 data packet for a vertex. Extend this class to store in the vertices the potential additional information you need (e.g. images, laser scans, ...). More...
class  Edge
struct  EdgeIDCompare
 order edges based on the internal ID, which is assigned to the edge in addEdge() More...
class  Vertex
 A general case Vertex for optimization. More...
struct  VertexIDCompare
 order vertices based on their ID More...

Public Types

enum  ActionType { AT_PREITERATION, AT_POSTITERATION, AT_NUM_ELEMENTS }
typedef std::vector
< OptimizableGraph::Edge * > 
EdgeContainer
 vector container for edges
typedef std::set
< HyperGraphAction * > 
HyperGraphActionSet
typedef std::vector
< OptimizableGraph::Vertex * > 
VertexContainer
 vector container for vertices

Public Member Functions

virtual bool addEdge (OptimizableGraph::Edge *e)
void addGraph (OptimizableGraph *g)
 adds all edges and vertices of the graph g to this graph.
bool addPostIterationAction (HyperGraphAction *action)
 add an action to be executed after each iteration
bool addPreIterationAction (HyperGraphAction *action)
 add an action to be executed before each iteration
virtual bool addVertex (OptimizableGraph::Vertex *v, Data *userData=0)
double chi2 () const
 returns the chi2 of the current configuration
std::set< int > dimensions () const
virtual void discardTop ()
 discard the last backup of the estimate for all variables by removing it from the stack
virtual void discardTop (HyperGraph::VertexSet &vset)
 ignore the latest stored element on the stack, remove it from the stack but do not restore the estimate
bool isSolverSuitable (const SolverProperty &solverProperty, const std::set< int > &vertDims=std::set< int >()) const
virtual bool load (std::istream &is, bool createEdges=true)
 load the graph from a stream. Uses the Factory singleton for creating the vertices and edges.
bool load (const char *filename, bool createEdges=true)
int maxDimension () const
 return the maximum dimension of all vertices in the graph
 OptimizableGraph ()
 empty constructor
virtual int optimize (int iterations, bool online=false)
virtual void pop ()
 pop (restore) the estimate of all variables from the stack
virtual void pop (HyperGraph::VertexSet &vset)
 pop (restore) the estimate a subset of the variables from the stack
virtual void postIteration (int)
 called at the end of an iteration (argument is the number of the iteration)
virtual void preIteration (int)
 called at the beginning of an iteration (argument is the number of the iteration)
virtual void push ()
 push the estimate of all variables onto a stack
virtual void push (HyperGraph::VertexSet &vset)
 push the estimate of a subset of the variables onto a stack
bool removePostIterationAction (HyperGraphAction *action)
 remove an action that should no longer be execured after each iteration
bool removePreIterationAction (HyperGraphAction *action)
 remove an action that should no longer be execured before each iteration
virtual bool save (std::ostream &os, int level=0) const
 save the graph to a stream. Again uses the Factory system.
bool save (const char *filename, int level=0) const
 function provided for convenience, see save() above
bool saveSubset (std::ostream &os, HyperGraph::VertexSet &vset, int level=0)
 save a subgraph to a stream. Again uses the Factory system.
bool saveSubset (std::ostream &os, HyperGraph::EdgeSet &eset)
 save a subgraph to a stream. Again uses the Factory system.
virtual void setFixed (HyperGraph::VertexSet &vset, bool fixed)
 fixes/releases a set of vertices
void setRenamedTypesFromString (const std::string &types)
Vertexvertex (int id)
 returns the vertex number id appropriately casted
const Vertexvertex (int id) const
 returns the vertex number id appropriately casted
virtual ~OptimizableGraph ()

Protected Attributes

bool _edge_has_id
std::vector< HyperGraphActionSet_graphActions
OptimizableGraph_lowerGraph
long long _nextEdgeId
std::list< Vertex * > _partialList
 this is the list of higher level vertices which need to be deleted.
std::map< std::string,
std::string > 
_renamedTypesLookup
std::list< Vertex * > _taintedList
 this is the list of higher level vertices whose connectivity and information has to be recomputed
OptimizableGraph_upperGraph

Detailed Description

This is an abstract class that represents one optimization problem. It specializes the general graph to contain special vertices and edges. The vertices represent parameters that can be optimized, while the edges represent constraints. This class also provides basic functionalities to handle the backup/restore of portions of the vertices.

Definition at line 46 of file optimizable_graph.h.


Member Typedef Documentation

vector container for edges

Definition at line 95 of file optimizable_graph.h.

Definition at line 53 of file optimizable_graph.h.

vector container for vertices

Definition at line 93 of file optimizable_graph.h.


Member Enumeration Documentation

Enumerator:
AT_PREITERATION 
AT_POSTITERATION 
AT_NUM_ELEMENTS 

Definition at line 48 of file optimizable_graph.h.


Constructor & Destructor Documentation

empty constructor

Definition at line 121 of file optimizable_graph.cpp.

Definition at line 127 of file optimizable_graph.cpp.


Member Function Documentation

adds a new edge. The edge should point to the vertices that it is connecting (setFrom/setTo).

Returns:
false if the insertion does not work (incompatible types of the vertices/missing vertex). true otherwise.

Definition at line 146 of file optimizable_graph.cpp.

adds all edges and vertices of the graph g to this graph.

Definition at line 544 of file optimizable_graph.cpp.

add an action to be executed after each iteration

Definition at line 658 of file optimizable_graph.cpp.

add an action to be executed before each iteration

Definition at line 664 of file optimizable_graph.cpp.

bool g2o::OptimizableGraph::addVertex ( OptimizableGraph::Vertex v,
Data userData = 0 
) [virtual]

adds a new vertex. The new vertex is then "taken".

Returns:
false if a vertex with the same id as v is already in the graph, true otherwise.

Definition at line 132 of file optimizable_graph.cpp.

double g2o::OptimizableGraph::chi2 ( ) const

returns the chi2 of the current configuration

Definition at line 157 of file optimizable_graph.cpp.

iterates over all vertices and returns a set of all the vertex dimensions in the graph

Definition at line 626 of file optimizable_graph.cpp.

discard the last backup of the estimate for all variables by removing it from the stack

Definition at line 183 of file optimizable_graph.cpp.

ignore the latest stored element on the stack, remove it from the stack but do not restore the estimate

Definition at line 207 of file optimizable_graph.cpp.

bool g2o::OptimizableGraph::isSolverSuitable ( const SolverProperty solverProperty,
const std::set< int > &  vertDims = std::set<int>() 
) const

test whether a solver is suitable for optimizing this graph.

Parameters:
solverPropertythe solver property to evaluate.
vertDimsshould equal to the set returned by dimensions() to avoid re-evaluating.

Definition at line 603 of file optimizable_graph.cpp.

virtual bool g2o::OptimizableGraph::load ( std::istream &  is,
bool  createEdges = true 
) [virtual]

load the graph from a stream. Uses the Factory singleton for creating the vertices and edges.

bool g2o::OptimizableGraph::load ( const char *  filename,
bool  createEdges = true 
)

Definition at line 376 of file optimizable_graph.cpp.

return the maximum dimension of all vertices in the graph

Definition at line 568 of file optimizable_graph.cpp.

int g2o::OptimizableGraph::optimize ( int  iterations,
bool  online = false 
) [virtual]

carry out n iterations

Returns:
the number of performed iterations

Reimplemented in g2o::SparseOptimizer, g2o::SparseOptimizerIncremental, and g2o::SparseOptimizerOnline.

Definition at line 155 of file optimizable_graph.cpp.

void g2o::OptimizableGraph::pop ( ) [virtual]

pop (restore) the estimate of all variables from the stack

Definition at line 175 of file optimizable_graph.cpp.

pop (restore) the estimate a subset of the variables from the stack

Reimplemented in g2o::SparseOptimizer.

Definition at line 199 of file optimizable_graph.cpp.

void g2o::OptimizableGraph::postIteration ( int  iter) [virtual]

called at the end of an iteration (argument is the number of the iteration)

Definition at line 647 of file optimizable_graph.cpp.

void g2o::OptimizableGraph::preIteration ( int  iter) [virtual]

called at the beginning of an iteration (argument is the number of the iteration)

Definition at line 636 of file optimizable_graph.cpp.

void g2o::OptimizableGraph::push ( ) [virtual]

push the estimate of all variables onto a stack

Definition at line 167 of file optimizable_graph.cpp.

push the estimate of a subset of the variables onto a stack

Reimplemented in g2o::SparseOptimizer.

Definition at line 191 of file optimizable_graph.cpp.

remove an action that should no longer be execured after each iteration

Definition at line 675 of file optimizable_graph.cpp.

remove an action that should no longer be execured before each iteration

Definition at line 670 of file optimizable_graph.cpp.

virtual bool g2o::OptimizableGraph::save ( std::ostream &  os,
int  level = 0 
) const [virtual]

save the graph to a stream. Again uses the Factory system.

bool g2o::OptimizableGraph::save ( const char *  filename,
int  level = 0 
) const

function provided for convenience, see save() above

Definition at line 386 of file optimizable_graph.cpp.

bool g2o::OptimizableGraph::saveSubset ( std::ostream &  os,
HyperGraph::VertexSet vset,
int  level = 0 
)

save a subgraph to a stream. Again uses the Factory system.

bool g2o::OptimizableGraph::saveSubset ( std::ostream &  os,
HyperGraph::EdgeSet eset 
)

save a subgraph to a stream. Again uses the Factory system.

void g2o::OptimizableGraph::setFixed ( HyperGraph::VertexSet vset,
bool  fixed 
) [virtual]

fixes/releases a set of vertices

Definition at line 215 of file optimizable_graph.cpp.

void g2o::OptimizableGraph::setRenamedTypesFromString ( const std::string &  types)

set the renamed types lookup from a string, format is for example: VERTEX_CAM=VERTEX_SE3:EXPMAP,EDGE_PROJECT_P2MC=EDGE_PROJECT_XYZ:EXPMAP This will change the occurance of VERTEX_CAM in the file to VERTEX_SE3:EXPMAP

Definition at line 577 of file optimizable_graph.cpp.

Vertex* g2o::OptimizableGraph::vertex ( int  id) [inline]

returns the vertex number id appropriately casted

Reimplemented from g2o::HyperGraph.

Definition at line 403 of file optimizable_graph.h.

const Vertex* g2o::OptimizableGraph::vertex ( int  id) const [inline]

returns the vertex number id appropriately casted

Reimplemented from g2o::HyperGraph.

Definition at line 406 of file optimizable_graph.h.


Member Data Documentation

Definition at line 515 of file optimizable_graph.h.

Definition at line 512 of file optimizable_graph.h.

Definition at line 509 of file optimizable_graph.h.

long long g2o::OptimizableGraph::_nextEdgeId [protected]

Definition at line 511 of file optimizable_graph.h.

this is the list of higher level vertices which need to be deleted.

Definition at line 507 of file optimizable_graph.h.

std::map<std::string, std::string> g2o::OptimizableGraph::_renamedTypesLookup [protected]

Definition at line 510 of file optimizable_graph.h.

this is the list of higher level vertices whose connectivity and information has to be recomputed

Definition at line 507 of file optimizable_graph.h.

Definition at line 509 of file optimizable_graph.h.


The documentation for this struct was generated from the following files:


re_vision
Author(s): Dorian Galvez-Lopez
autogenerated on Sun Jan 5 2014 11:34:30