Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Friends
g2o::SparseOptimizer Struct Reference

#include <graph_optimizer_sparse.h>

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

List of all members.

Public Types

enum  Method { GaussNewton, LevenbergMarquardt }

Public Member Functions

double activeChi2 () const
const EdgeContaineractiveEdges () const
const VertexContaineractiveVertices () const
virtual void clear ()
void computeActiveErrors ()
virtual void computeInitialGuess ()
bool computeMarginals ()
bool computeMarginals (SparseBlockMatrix< MatrixXd > &spinv, const std::vector< std::pair< int, int > > &blockIndices)
double currentLambda () const
void discardTop (SparseOptimizer::VertexContainer &vlist)
EdgeContainer::const_iterator findActiveEdge (OptimizableGraph::Edge *e) const
VertexContainer::const_iterator findActiveVertex (OptimizableGraph::Vertex *v) const
virtual VertexfindGauge ()
bool gaugeFreedom ()
const VertexContainerindexMapping () const
virtual bool initializeOptimization (HyperGraph::EdgeSet &eset)
virtual bool initializeOptimization (HyperGraph::VertexSet &vset, int level=0)
virtual bool initializeOptimization (int level=0)
void linearizeSystem ()
int maxTrialsAfterFailure () const
Method method () const
int optimize (int iterations, bool online=false)
void pop (SparseOptimizer::VertexContainer &vlist)
void pop (HyperGraph::VertexSet &vlist)
void push (SparseOptimizer::VertexContainer &vlist)
void push (HyperGraph::VertexSet &vlist)
virtual bool removeVertex (Vertex *v)
 removes a vertex from the graph. Returns true on success (vertex was present)
void setForceStopFlag (bool *flag)
void setMaxTrialsAfterFailure (int max_trials)
void setMethod (Method method)
void setSolver (Solver *solver)
void setUserLambdaInit (double lambda)
void setVerbose (bool verbose)
const Solversolver () const
Solversolver ()
 SparseOptimizer ()
bool terminate ()
void update (double *update)
virtual bool updateInitialization (HyperGraph::VertexSet &vset, HyperGraph::EdgeSet &eset)
double userLambdaInit ()
bool verbose () const
virtual ~SparseOptimizer ()

Public Attributes

G2OBatchStatistics_statistics
 global statistics of the optimizer, e.g., timing, num-non-zeros

Protected Member Functions

bool buildIndexMapping (SparseOptimizer::VertexContainer &vlist)
void clearIndexMapping ()
double computeLambdaInit ()
double computeScale (double currentLMLambda, Solver *solver)
void sortVectorContainers ()

Protected Attributes

EdgeContainer _activeEdges
 sorted according to EdgeIDCompare
VertexContainer _activeVertices
 sorted according to VertexIDCompare
double _currentLambda
bool_forceStopFlag
double _goodStepLowerScale
 lower bound for lambda decrease if a good LM step
double _goodStepUpperScale
 upper bound for lambda decrease if a good LM step
VertexContainer _ivMap
int _maxTrialsAfterFailure
Method _method
Solver_solver
double _tau
double _userLambdaInit
bool _verbose

Friends

class ActivePathCostFunction

Detailed Description

Definition at line 35 of file graph_optimizer_sparse.h.


Member Enumeration Documentation

Enumerator:
GaussNewton 
LevenbergMarquardt 

Definition at line 37 of file graph_optimizer_sparse.h.


Constructor & Destructor Documentation

Definition at line 39 of file graph_optimizer_sparse.cpp.

Definition at line 54 of file graph_optimizer_sparse.cpp.


Member Function Documentation

Returns the cached chi2 of the active portion of the graph

Definition at line 76 of file graph_optimizer_sparse.cpp.

The edges active in the current optimization

Definition at line 177 of file graph_optimizer_sparse.h.

The vertices active in the current optimization

Definition at line 172 of file graph_optimizer_sparse.h.

Builds the mapping of the active vertices to the (block) row / column in the Hessian

Definition at line 170 of file graph_optimizer_sparse.cpp.

void g2o::SparseOptimizer::clear ( void  ) [virtual]

Clears the graph, and polishes some intermediate structures

Reimplemented from g2o::HyperGraph.

Definition at line 744 of file graph_optimizer_sparse.cpp.

Definition at line 207 of file graph_optimizer_sparse.cpp.

Computes the error vectors of all edges in the activeSet, and caches them

Definition at line 61 of file graph_optimizer_sparse.cpp.

Propagates an initial guess from the vertex specified as origin. It should be called after initializeOptimization(...), as it relies on the _activeVertices/_edges structures. It constructs a set of trees starting from the nodes in the graph which are fixed and eligible for preforming optimization. The trees are constructed by utilizing a cost-function specified.

Parameters:
costFunction,:the cost function used maxDistance: the distance where to stop the search

Definition at line 373 of file graph_optimizer_sparse.cpp.

Helper for Levenberg, this function computes the initial damping factor, if the user did not specify an own value, see setUserLambdaInit()

Definition at line 218 of file graph_optimizer_sparse.cpp.

Computes the block diagonal elements of the inverted hessian and stores them in the nodes of the graph.

Definition at line 856 of file graph_optimizer_sparse.cpp.

bool g2o::SparseOptimizer::computeMarginals ( SparseBlockMatrix< MatrixXd > &  spinv,
const std::vector< std::pair< int, int > > &  blockIndices 
)

Computes the blocks of the inverse of the specified pattern. the pattern is given via pairs <row, col> of the blocks in the hessian

Parameters:
blockIndices,:the pattern
spinv,:the sparse block matrix with the result
Returns:
false if the operation is not supported by the solver

Definition at line 863 of file graph_optimizer_sparse.cpp.

double g2o::SparseOptimizer::computeScale ( double  currentLMLambda,
Solver solver 
) [protected]

Definition at line 235 of file graph_optimizer_sparse.cpp.

double g2o::SparseOptimizer::currentLambda ( ) const [inline]

Return the currently used damping factor

Definition at line 266 of file graph_optimizer_sparse.h.

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

Definition at line 821 of file graph_optimizer_sparse.cpp.

SparseOptimizer::EdgeContainer::const_iterator g2o::SparseOptimizer::findActiveEdge ( OptimizableGraph::Edge e) const

Search for an edge in _activeEdges and return the iterator pointing to it getActiveEdges().end() if not found

Definition at line 765 of file graph_optimizer_sparse.cpp.

SparseOptimizer::VertexContainer::const_iterator g2o::SparseOptimizer::findActiveVertex ( OptimizableGraph::Vertex v) const

Search for an edge in _activeEdges and return the iterator pointing to it getActiveVertices().end() if not found

Definition at line 753 of file graph_optimizer_sparse.cpp.

Finds a gauge in the graph to remove the undefined dof. The gauge should be fixed() and then the optimization can work (if no additional dof are in the system. The default implementation returns a node with maximum dimension.

Definition at line 92 of file graph_optimizer_sparse.cpp.

Definition at line 126 of file graph_optimizer_sparse.cpp.

The index mapping of the vertices

Definition at line 167 of file graph_optimizer_sparse.h.

Initializes the structures for optimizing a portion of the graph specified by a subset of edges. Before calling it be sure to invoke marginalized() and fixed() to the vertices you want to include in the schurr complement or to set as fixed during the optimization.

Parameters:
eset,:the subgraph to be optimized.
Returns:
false if somethings goes wrong

Definition at line 338 of file graph_optimizer_sparse.cpp.

bool g2o::SparseOptimizer::initializeOptimization ( HyperGraph::VertexSet vset,
int  level = 0 
) [virtual]

Initializes the structures for optimizing a portion of the graph specified by a subset of vertices. Before calling it be sure to invoke marginalized() and fixed() to the vertices you want to include in the schurr complement or to set as fixed during the optimization.

Parameters:
vset,:the subgraph to be optimized.
level,:is the level (in multilevel optimization)
Returns:
false if somethings goes wrong

Definition at line 263 of file graph_optimizer_sparse.cpp.

bool g2o::SparseOptimizer::initializeOptimization ( int  level = 0) [virtual]

Initializes the structures for optimizing the whole graph. Before calling it be sure to invoke marginalized() and fixed() to the vertices you want to include in the schurr complement or to set as fixed during the optimization.

Parameters:
level,:is the level (in multilevel optimization)
Returns:
false if somethings goes wrong

Definition at line 247 of file graph_optimizer_sparse.cpp.

Linearizes the system by computing the Jacobians for the nodes and edges in the graph

Definition at line 669 of file graph_optimizer_sparse.cpp.

Get the number of inner iterations for Levenberg-Marquardt

Definition at line 277 of file graph_optimizer_sparse.h.

Accessor for the optimization method (gauss-newton or levenberg-marquardt)

Definition at line 150 of file graph_optimizer_sparse.h.

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

Starts one optimization run given the current configuration of the graph, and the current settings stored in the class instance. It can be called only after initializeOptimization

Reimplemented from g2o::OptimizableGraph.

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

Definition at line 447 of file graph_optimizer_sparse.cpp.

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

Definition at line 785 of file graph_optimizer_sparse.cpp.

void g2o::SparseOptimizer::pop ( HyperGraph::VertexSet vlist) [virtual]

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

Reimplemented from g2o::OptimizableGraph.

Definition at line 808 of file graph_optimizer_sparse.cpp.

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

Definition at line 777 of file graph_optimizer_sparse.cpp.

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

Reimplemented from g2o::OptimizableGraph.

Definition at line 793 of file graph_optimizer_sparse.cpp.

removes a vertex from the graph. Returns true on success (vertex was present)

Reimplemented from g2o::HyperGraph.

Definition at line 883 of file graph_optimizer_sparse.cpp.

Sets a variable checked at every iteration to force a user stop. The iteration exits when the variable is true;

Definition at line 876 of file graph_optimizer_sparse.cpp.

The number of internal iteration if an update step increases chi^2 within Levenberg-Marquardt

Definition at line 869 of file graph_optimizer_sparse.cpp.

Definition at line 835 of file graph_optimizer_sparse.cpp.

Definition at line 842 of file graph_optimizer_sparse.cpp.

void g2o::SparseOptimizer::setUserLambdaInit ( double  lambda)

Specify the initial lambda used for the first iteraion, if not given the SparseOptimizer tries to compute a suitable value

Definition at line 849 of file graph_optimizer_sparse.cpp.

Definition at line 828 of file graph_optimizer_sparse.cpp.

const Solver* g2o::SparseOptimizer::solver ( ) const [inline]

The solver used by the optimizer

Definition at line 198 of file graph_optimizer_sparse.h.

Definition at line 199 of file graph_optimizer_sparse.h.

Definition at line 735 of file graph_optimizer_sparse.cpp.

If external stop flag is given, return its state. False otherwise

Definition at line 162 of file graph_optimizer_sparse.h.

void g2o::SparseOptimizer::update ( double *  update)

Update the estimate of the active vertices

Parameters:
update,:the double vector containing the stacked elements of the increments on the vertices.

Reimplemented in g2o::SparseOptimizerOnline.

Definition at line 684 of file graph_optimizer_sparse.cpp.

HACK updating the internal structures for online processing

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

Definition at line 697 of file graph_optimizer_sparse.cpp.

Return the lambda set by the user, if < 0 the SparseOptimizer will compute the initial lambda

Definition at line 232 of file graph_optimizer_sparse.h.

bool g2o::SparseOptimizer::verbose ( ) const [inline]

Verbose information during optimization

Definition at line 143 of file graph_optimizer_sparse.h.


Friends And Related Function Documentation

friend class ActivePathCostFunction [friend]

Definition at line 39 of file graph_optimizer_sparse.h.


Member Data Documentation

sorted according to EdgeIDCompare

Definition at line 289 of file graph_optimizer_sparse.h.

sorted according to VertexIDCompare

Definition at line 288 of file graph_optimizer_sparse.h.

Definition at line 284 of file graph_optimizer_sparse.h.

Definition at line 280 of file graph_optimizer_sparse.h.

lower bound for lambda decrease if a good LM step

Definition at line 299 of file graph_optimizer_sparse.h.

upper bound for lambda decrease if a good LM step

Definition at line 301 of file graph_optimizer_sparse.h.

Definition at line 287 of file graph_optimizer_sparse.h.

Definition at line 285 of file graph_optimizer_sparse.h.

Definition at line 283 of file graph_optimizer_sparse.h.

Definition at line 293 of file graph_optimizer_sparse.h.

global statistics of the optimizer, e.g., timing, num-non-zeros

Definition at line 319 of file graph_optimizer_sparse.h.

double g2o::SparseOptimizer::_tau [protected]

Definition at line 296 of file graph_optimizer_sparse.h.

Definition at line 297 of file graph_optimizer_sparse.h.

Definition at line 281 of file graph_optimizer_sparse.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