#include <sparse_optimizer.h>
Public Types | |
enum | { AT_COMPUTEACTIVERROR = OptimizableGraph::AT_NUM_ELEMENTS, AT_NUM_ELEMENTS } |
Public Types inherited from g2o::OptimizableGraph | |
enum | ActionType { AT_PREITERATION, AT_POSTITERATION, AT_NUM_ELEMENTS } |
typedef std::vector< OptimizableGraph::Edge * > | EdgeContainer |
vector container for edges More... | |
typedef std::set< HyperGraphAction * > | HyperGraphActionSet |
typedef std::vector< OptimizableGraph::Vertex * > | VertexContainer |
vector container for vertices More... | |
Public Types inherited from g2o::HyperGraph | |
typedef std::set< Edge * > | EdgeSet |
typedef std::bitset< HyperGraph::HGET_NUM_ELEMS > | GraphElemBitset |
enum | HyperGraphElementType { HGET_VERTEX, HGET_EDGE, HGET_PARAMETER, HGET_CACHE, HGET_DATA, HGET_NUM_ELEMS } |
enum of all the types we have in our graphs More... | |
typedef std::vector< Vertex * > | VertexContainer |
typedef std::tr1::unordered_map< int, Vertex * > | VertexIDMap |
typedef std::set< Vertex * > | VertexSet |
Public Member Functions | |
double | activeChi2 () const |
const EdgeContainer & | activeEdges () const |
the edges active in the current optimization More... | |
double | activeRobustChi2 () const |
const VertexContainer & | activeVertices () const |
the vertices active in the current optimization More... | |
bool | addComputeErrorAction (HyperGraphAction *action) |
add an action to be executed before the error vectors are computed More... | |
const OptimizationAlgorithm * | algorithm () const |
the solver used by the optimizer More... | |
const BatchStatisticsContainer & | batchStatistics () const |
BatchStatisticsContainer & | batchStatistics () |
virtual void | clear () |
void | computeActiveErrors () |
bool | computeBatchStatistics () const |
virtual void | computeInitialGuess () |
virtual void | computeInitialGuess (EstimatePropagatorCost &propagator) |
bool | computeMarginals (SparseBlockMatrix< MatrixXd > &spinv, const std::vector< std::pair< int, int > > &blockIndices) |
bool | computeMarginals (SparseBlockMatrix< MatrixXd > &spinv, const Vertex *vertex) |
bool | computeMarginals (SparseBlockMatrix< MatrixXd > &spinv, const VertexContainer &vertices) |
void | discardTop (SparseOptimizer::VertexContainer &vlist) |
ignore the latest stored element on the stack, remove it from the stack but do not restore the estimate More... | |
void | discardTop () |
same as above, but for the active vertices More... | |
EdgeContainer::const_iterator | findActiveEdge (const OptimizableGraph::Edge *e) const |
VertexContainer::const_iterator | findActiveVertex (const OptimizableGraph::Vertex *v) const |
virtual Vertex * | findGauge () |
finds a gauge in the graph to remove the undefined dof. More... | |
bool * | forceStopFlag () const |
bool | gaugeFreedom () |
const VertexContainer & | indexMapping () const |
the index mapping of the vertices More... | |
virtual bool | initializeOptimization (HyperGraph::EdgeSet &eset) |
virtual bool | initializeOptimization (HyperGraph::VertexSet &vset, int level=0) |
virtual bool | initializeOptimization (int level=0) |
int | optimize (int iterations, bool online=false) |
void | pop (SparseOptimizer::VertexContainer &vlist) |
pop (restore) the estimate a subset of the variables from the stack More... | |
void | pop (HyperGraph::VertexSet &vlist) |
pop (restore) the estimate a subset of the variables from the stack More... | |
void | pop () |
pop (restore) the estimate of the active vertices from the stack More... | |
void | push (SparseOptimizer::VertexContainer &vlist) |
push the estimate of a subset of the variables onto a stack More... | |
void | push (HyperGraph::VertexSet &vlist) |
push the estimate of a subset of the variables onto a stack More... | |
void | push () |
push all the active vertices onto a stack More... | |
bool | removeComputeErrorAction (HyperGraphAction *action) |
remove an action that should no longer be execured before computing the error vectors More... | |
virtual bool | removeVertex (HyperGraph::Vertex *v) |
void | setAlgorithm (OptimizationAlgorithm *algorithm) |
void | setComputeBatchStatistics (bool computeBatchStatistics) |
void | setForceStopFlag (bool *flag) |
virtual void | setToOrigin () |
void | setVerbose (bool verbose) |
OptimizationAlgorithm * | solver () |
SparseOptimizer () | |
bool | terminate () |
if external stop flag is given, return its state. False otherwise More... | |
virtual bool | updateInitialization (HyperGraph::VertexSet &vset, HyperGraph::EdgeSet &eset) |
bool | verbose () const |
verbose information during optimization More... | |
virtual | ~SparseOptimizer () |
Public Member Functions inherited from g2o::OptimizableGraph | |
virtual bool | addEdge (HyperGraph::Edge *e) |
void | addGraph (OptimizableGraph *g) |
adds all edges and vertices of the graph g to this graph. More... | |
bool | addParameter (Parameter *p) |
bool | addPostIterationAction (HyperGraphAction *action) |
add an action to be executed after each iteration More... | |
bool | addPreIterationAction (HyperGraphAction *action) |
add an action to be executed before each iteration More... | |
virtual bool | addVertex (HyperGraph::Vertex *v, Data *userData) |
virtual bool | addVertex (HyperGraph::Vertex *v) |
double | chi2 () const |
returns the chi2 of the current configuration More... | |
virtual void | clearParameters () |
std::set< int > | dimensions () const |
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 More... | |
bool | isSolverSuitable (const OptimizationAlgorithmProperty &solverProperty, const std::set< int > &vertDims=std::set< int >()) const |
JacobianWorkspace & | jacobianWorkspace () |
the workspace for storing the Jacobians of the graph More... | |
const JacobianWorkspace & | jacobianWorkspace () 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. More... | |
bool | load (const char *filename, bool createEdges=true) |
int | maxDimension () const |
return the maximum dimension of all vertices in the graph More... | |
OptimizableGraph () | |
empty constructor More... | |
Parameter * | parameter (int id) |
virtual void | postIteration (int) |
called at the end of an iteration (argument is the number of the iteration) More... | |
virtual void | preIteration (int) |
called at the beginning of an iteration (argument is the number of the iteration) More... | |
bool | removePostIterationAction (HyperGraphAction *action) |
remove an action that should no longer be execured after each iteration More... | |
bool | removePreIterationAction (HyperGraphAction *action) |
remove an action that should no longer be execured before each iteration More... | |
virtual bool | save (std::ostream &os, int level=0) const |
save the graph to a stream. Again uses the Factory system. More... | |
bool | save (const char *filename, int level=0) const |
function provided for convenience, see save() above More... | |
bool | saveEdge (std::ostream &os, Edge *e) const |
bool | saveSubset (std::ostream &os, HyperGraph::VertexSet &vset, int level=0) |
save a subgraph to a stream. Again uses the Factory system. More... | |
bool | saveSubset (std::ostream &os, HyperGraph::EdgeSet &eset) |
save a subgraph to a stream. Again uses the Factory system. More... | |
bool | saveVertex (std::ostream &os, Vertex *v) const |
virtual void | setFixed (HyperGraph::VertexSet &vset, bool fixed) |
fixes/releases a set of vertices More... | |
void | setRenamedTypesFromString (const std::string &types) |
bool | verifyInformationMatrices (bool verbose=false) const |
Vertex * | vertex (int id) |
returns the vertex number id appropriately casted More... | |
const Vertex * | vertex (int id) const |
returns the vertex number id appropriately casted More... | |
virtual | ~OptimizableGraph () |
Public Member Functions inherited from g2o::HyperGraph | |
virtual bool | changeId (Vertex *v, int newId) |
const EdgeSet & | edges () const |
EdgeSet & | edges () |
HyperGraph () | |
constructs an empty hyper graph More... | |
virtual bool | removeEdge (Edge *e) |
removes a vertex from the graph. Returns true on success (edge was present) More... | |
Vertex * | vertex (int id) |
returns a vertex id in the hyper-graph, or 0 if the vertex id is not present More... | |
const Vertex * | vertex (int id) const |
returns a vertex id in the hyper-graph, or 0 if the vertex id is not present More... | |
const VertexIDMap & | vertices () const |
VertexIDMap & | vertices () |
virtual | ~HyperGraph () |
destroys the hyper-graph and all the vertices of the graph More... | |
Protected Member Functions | |
bool | buildIndexMapping (SparseOptimizer::VertexContainer &vlist) |
void | clearIndexMapping () |
void | sortVectorContainers () |
Protected Attributes | |
EdgeContainer | _activeEdges |
sorted according to EdgeIDCompare More... | |
VertexContainer | _activeVertices |
sorted according to VertexIDCompare More... | |
OptimizationAlgorithm * | _algorithm |
BatchStatisticsContainer | _batchStatistics |
global statistics of the optimizer, e.g., timing, num-non-zeros More... | |
bool | _computeBatchStatistics |
bool * | _forceStopFlag |
VertexContainer | _ivMap |
bool | _verbose |
Protected Attributes inherited from g2o::OptimizableGraph | |
bool | _edge_has_id |
std::vector< HyperGraphActionSet > | _graphActions |
JacobianWorkspace | _jacobianWorkspace |
long long | _nextEdgeId |
ParameterContainer | _parameters |
std::map< std::string, std::string > | _renamedTypesLookup |
Protected Attributes inherited from g2o::HyperGraph | |
EdgeSet | _edges |
VertexIDMap | _vertices |
Friends | |
class | ActivePathCostFunction |
Additional Inherited Members | |
Static Public Member Functions inherited from g2o::OptimizableGraph | |
static bool | initMultiThreading () |
Definition at line 45 of file sparse_optimizer.h.
anonymous enum |
Enumerator | |
---|---|
AT_COMPUTEACTIVERROR | |
AT_NUM_ELEMENTS |
Definition at line 48 of file sparse_optimizer.h.
g2o::SparseOptimizer::SparseOptimizer | ( | ) |
Definition at line 50 of file sparse_optimizer.cpp.
|
virtual |
Definition at line 56 of file sparse_optimizer.cpp.
double g2o::SparseOptimizer::activeChi2 | ( | ) | const |
returns the cached chi2 of the active portion of the graph
Definition at line 90 of file sparse_optimizer.cpp.
|
inline |
the edges active in the current optimization
Definition at line 195 of file sparse_optimizer.h.
double g2o::SparseOptimizer::activeRobustChi2 | ( | ) | const |
returns the cached chi2 of the active portion of the graph. In contrast to activeChi2() this functions considers the weighting of the error according to the robustification of the error functions.
Definition at line 100 of file sparse_optimizer.cpp.
|
inline |
the vertices active in the current optimization
Definition at line 193 of file sparse_optimizer.h.
bool g2o::SparseOptimizer::addComputeErrorAction | ( | HyperGraphAction * | action | ) |
add an action to be executed before the error vectors are computed
Definition at line 589 of file sparse_optimizer.cpp.
|
inline |
the solver used by the optimizer
Definition at line 217 of file sparse_optimizer.h.
|
inline |
Linearizes the system by computing the Jacobians for the nodes and edges in the graph returns the set of batch statistics about the optimisation
Definition at line 271 of file sparse_optimizer.h.
|
inline |
returns the set of batch statistics about the optimisation
Definition at line 275 of file sparse_optimizer.h.
|
protected |
builds the mapping of the active vertices to the (block) row / column in the Hessian
Definition at line 166 of file sparse_optimizer.cpp.
|
virtual |
clears the graph, and polishes some intermediate structures Note that this only removes nodes / edges. Parameters can be removed with clearParameters().
Reimplemented from g2o::HyperGraph.
Definition at line 489 of file sparse_optimizer.cpp.
|
protected |
Definition at line 192 of file sparse_optimizer.cpp.
void g2o::SparseOptimizer::computeActiveErrors | ( | ) |
computes the error vectors of all edges in the activeSet, and caches them
Definition at line 61 of file sparse_optimizer.cpp.
|
inline |
Definition at line 279 of file sparse_optimizer.h.
|
virtual |
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 utlizing a cost-function specified.
costFunction | the cost function used maxDistance: the distance where to stop the search |
Definition at line 300 of file sparse_optimizer.cpp.
|
virtual |
Same as above but using a specific propagator
Definition at line 306 of file sparse_optimizer.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
blockIndices | the pattern |
spinv | the sparse block matrix with the result |
Definition at line 570 of file sparse_optimizer.cpp.
|
inline |
computes the inverse of the specified vertex.
vertex | the vertex whose state is to be marginalised |
spinv | the sparse block matrix with the result |
Definition at line 138 of file sparse_optimizer.h.
|
inline |
computes the inverse of the set specified vertices, assembled into a single covariance matrix.
vertex | the pattern |
spinv | the sparse block matrix with the result |
Definition at line 153 of file sparse_optimizer.h.
void g2o::SparseOptimizer::discardTop | ( | SparseOptimizer::VertexContainer & | vlist | ) |
ignore the latest stored element on the stack, remove it from the stack but do not restore the estimate
Definition at line 550 of file sparse_optimizer.cpp.
|
virtual |
same as above, but for the active vertices
Reimplemented from g2o::OptimizableGraph.
Definition at line 610 of file sparse_optimizer.cpp.
SparseOptimizer::EdgeContainer::const_iterator g2o::SparseOptimizer::findActiveEdge | ( | const 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 506 of file sparse_optimizer.cpp.
SparseOptimizer::VertexContainer::const_iterator g2o::SparseOptimizer::findActiveVertex | ( | const OptimizableGraph::Vertex * | v | ) | const |
search for an edge in _activeVertices and return the iterator pointing to it getActiveVertices().end() if not found
Definition at line 496 of file sparse_optimizer.cpp.
|
virtual |
finds a gauge in the graph to remove the undefined dof.
Definition at line 116 of file sparse_optimizer.cpp.
|
inline |
Definition at line 185 of file sparse_optimizer.h.
bool g2o::SparseOptimizer::gaugeFreedom | ( | ) |
Definition at line 137 of file sparse_optimizer.cpp.
|
inline |
the index mapping of the vertices
Definition at line 191 of file sparse_optimizer.h.
|
virtual |
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 schur complement or to set as fixed during the optimization.
eset | the subgraph to be optimized. |
Definition at line 269 of file sparse_optimizer.cpp.
|
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 schur complement or to set as fixed during the optimization.
vset | the subgraph to be optimized. |
level | is the level (in multilevel optimization) |
Definition at line 206 of file sparse_optimizer.cpp.
|
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 schur complement or to set as fixed during the optimization.
level | is the level (in multilevel optimization) |
Definition at line 199 of file sparse_optimizer.cpp.
|
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.
Definition at line 354 of file sparse_optimizer.cpp.
void g2o::SparseOptimizer::pop | ( | SparseOptimizer::VertexContainer & | vlist | ) |
pop (restore) the estimate a subset of the variables from the stack
Definition at line 522 of file sparse_optimizer.cpp.
|
virtual |
pop (restore) the estimate a subset of the variables from the stack
Reimplemented from g2o::OptimizableGraph.
Definition at line 539 of file sparse_optimizer.cpp.
|
virtual |
pop (restore) the estimate of the active vertices from the stack
Reimplemented from g2o::OptimizableGraph.
Definition at line 605 of file sparse_optimizer.cpp.
void g2o::SparseOptimizer::push | ( | SparseOptimizer::VertexContainer & | vlist | ) |
push the estimate of a subset of the variables onto a stack
Definition at line 516 of file sparse_optimizer.cpp.
|
virtual |
push the estimate of a subset of the variables onto a stack
Reimplemented from g2o::OptimizableGraph.
Definition at line 528 of file sparse_optimizer.cpp.
|
virtual |
push all the active vertices onto a stack
Reimplemented from g2o::OptimizableGraph.
Definition at line 600 of file sparse_optimizer.cpp.
bool g2o::SparseOptimizer::removeComputeErrorAction | ( | HyperGraphAction * | action | ) |
remove an action that should no longer be execured before computing the error vectors
Definition at line 595 of file sparse_optimizer.cpp.
|
virtual |
Remove a vertex. If the vertex is contained in the currently active set of vertices, then the internal temporary structures are cleaned, e.g., the index mapping is erased. In case you need the index mapping for manipulating the graph, you have to store it in your own copy.
Reimplemented from g2o::HyperGraph.
Definition at line 579 of file sparse_optimizer.cpp.
void g2o::SparseOptimizer::setAlgorithm | ( | OptimizationAlgorithm * | algorithm | ) |
Definition at line 561 of file sparse_optimizer.cpp.
void g2o::SparseOptimizer::setComputeBatchStatistics | ( | bool | computeBatchStatistics | ) |
Definition at line 437 of file sparse_optimizer.cpp.
void g2o::SparseOptimizer::setForceStopFlag | ( | bool * | flag | ) |
sets a variable checked at every iteration to force a user stop. The iteration exits when the variable is true;
Definition at line 574 of file sparse_optimizer.cpp.
|
virtual |
sets all vertices to their origin.
Definition at line 293 of file sparse_optimizer.cpp.
void g2o::SparseOptimizer::setVerbose | ( | bool | verbose | ) |
Definition at line 556 of file sparse_optimizer.cpp.
|
inline |
Definition at line 218 of file sparse_optimizer.h.
|
protected |
Definition at line 482 of file sparse_optimizer.cpp.
|
inline |
if external stop flag is given, return its state. False otherwise
Definition at line 188 of file sparse_optimizer.h.
|
virtual |
HACK updating the internal structures for online processing
Definition at line 446 of file sparse_optimizer.cpp.
|
inline |
verbose information during optimization
Definition at line 178 of file sparse_optimizer.h.
|
friend |
Definition at line 53 of file sparse_optimizer.h.
|
protected |
sorted according to EdgeIDCompare
Definition at line 295 of file sparse_optimizer.h.
|
protected |
sorted according to VertexIDCompare
Definition at line 294 of file sparse_optimizer.h.
|
protected |
Definition at line 299 of file sparse_optimizer.h.
|
protected |
global statistics of the optimizer, e.g., timing, num-non-zeros
Definition at line 307 of file sparse_optimizer.h.
|
protected |
Definition at line 308 of file sparse_optimizer.h.
|
protected |
Definition at line 290 of file sparse_optimizer.h.
|
protected |
Definition at line 293 of file sparse_optimizer.h.
|
protected |
Definition at line 291 of file sparse_optimizer.h.