g2o
|
#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::set< HyperGraphAction * > | HyperGraphActionSet |
typedef std::vector< OptimizableGraph::Vertex * > | VertexContainer |
vector container for vertices More... | |
typedef std::vector< OptimizableGraph::Edge * > | EdgeContainer |
vector container for edges More... | |
Public Types inherited from g2o::HyperGraph | |
typedef std::bitset< HyperGraph::HGET_NUM_ELEMS > | GraphElemBitset |
typedef std::set< Edge * > | EdgeSet |
typedef std::set< Vertex * > | VertexSet |
typedef std::unordered_map< int, Vertex * > | VertexIDMap |
typedef std::vector< Vertex * > | VertexContainer |
Public Member Functions | |
SparseOptimizer () | |
virtual | ~SparseOptimizer () |
virtual bool | initializeOptimization (HyperGraph::EdgeSet &eset) |
virtual bool | initializeOptimization (HyperGraph::VertexSet &vset, int level=0) |
virtual bool | initializeOptimization (int level=0) |
virtual bool | updateInitialization (HyperGraph::VertexSet &vset, HyperGraph::EdgeSet &eset) |
virtual void | computeInitialGuess () |
virtual void | computeInitialGuess (EstimatePropagatorCost &propagator) |
virtual void | setToOrigin () |
int | optimize (int iterations, bool online=false) |
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) |
virtual Vertex * | findGauge () |
finds a gauge in the graph to remove the undefined dof. More... | |
bool | gaugeFreedom () |
double | activeChi2 () const |
double | activeRobustChi2 () const |
bool | verbose () const |
verbose information during optimization More... | |
void | setVerbose (bool verbose) |
void | setForceStopFlag (bool *flag) |
bool * | forceStopFlag () const |
bool | terminate () |
if external stop flag is given, return its state. False otherwise More... | |
const VertexContainer & | indexMapping () const |
the index mapping of the vertices More... | |
const VertexContainer & | activeVertices () const |
the vertices active in the current optimization More... | |
const EdgeContainer & | activeEdges () const |
the edges active in the current optimization More... | |
virtual bool | removeVertex (HyperGraph::Vertex *v, bool detach=false) |
VertexContainer::const_iterator | findActiveVertex (const OptimizableGraph::Vertex *v) const |
EdgeContainer::const_iterator | findActiveEdge (const OptimizableGraph::Edge *e) const |
const OptimizationAlgorithm * | algorithm () const |
the solver used by the optimizer More... | |
OptimizationAlgorithm * | solver () |
void | setAlgorithm (OptimizationAlgorithm *algorithm) |
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... | |
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 | 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... | |
virtual void | clear () |
void | computeActiveErrors () |
const BatchStatisticsContainer & | batchStatistics () const |
BatchStatisticsContainer & | batchStatistics () |
void | setComputeBatchStatistics (bool computeBatchStatistics) |
bool | computeBatchStatistics () const |
bool | addComputeErrorAction (HyperGraphAction *action) |
add an action to be executed before the error vectors are computed More... | |
bool | removeComputeErrorAction (HyperGraphAction *action) |
remove an action that should no longer be execured before computing the error vectors More... | |
Public Member Functions inherited from g2o::OptimizableGraph | |
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... | |
OptimizableGraph () | |
empty constructor More... | |
virtual | ~OptimizableGraph () |
void | addGraph (OptimizableGraph *g) |
adds all edges and vertices of the graph g to this graph. More... | |
virtual bool | addVertex (HyperGraph::Vertex *v, Data *userData) |
virtual bool | addVertex (HyperGraph::Vertex *v) |
virtual bool | addEdge (HyperGraph::Edge *e) |
virtual bool | setEdgeVertex (HyperGraph::Edge *e, int pos, HyperGraph::Vertex *v) |
double | chi2 () const |
returns the chi2 of the current configuration More... | |
int | maxDimension () const |
return the maximum dimension of all vertices in the graph More... | |
std::set< int > | dimensions () const |
virtual void | preIteration (int) |
called at the beginning of an iteration (argument is the number of the iteration) More... | |
virtual void | postIteration (int) |
called at the end of an iteration (argument is the number of the iteration) More... | |
bool | addPreIterationAction (HyperGraphAction *action) |
add an action to be executed before each iteration More... | |
bool | addPostIterationAction (HyperGraphAction *action) |
add an action to be executed after each iteration More... | |
bool | removePreIterationAction (HyperGraphAction *action) |
remove an action that should no longer be execured before each iteration More... | |
bool | removePostIterationAction (HyperGraphAction *action) |
remove an action that should no longer be execured after each iteration More... | |
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) |
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 | 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... | |
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... | |
virtual void | setFixed (HyperGraph::VertexSet &vset, bool fixed) |
fixes/releases a set of vertices More... | |
void | setRenamedTypesFromString (const std::string &types) |
bool | isSolverSuitable (const OptimizationAlgorithmProperty &solverProperty, const std::set< int > &vertDims=std::set< int >()) const |
virtual void | clearParameters () |
bool | addParameter (Parameter *p) |
Parameter * | parameter (int id) |
bool | verifyInformationMatrices (bool verbose=false) const |
bool | saveVertex (std::ostream &os, Vertex *v) const |
bool | saveParameter (std::ostream &os, Parameter *v) const |
bool | saveEdge (std::ostream &os, Edge *e) const |
bool | saveUserData (std::ostream &os, HyperGraph::Data *v) const |
JacobianWorkspace & | jacobianWorkspace () |
the workspace for storing the Jacobians of the graph More... | |
const JacobianWorkspace & | jacobianWorkspace () const |
ParameterContainer & | parameters () |
const ParameterContainer & | parameters () const |
Public Member Functions inherited from g2o::HyperGraph | |
HyperGraph () | |
constructs an empty hyper graph More... | |
virtual | ~HyperGraph () |
destroys the hyper-graph and all the vertices of the graph 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... | |
virtual bool | removeEdge (Edge *e) |
removes a vertex from the graph. Returns true on success (edge was present) More... | |
const VertexIDMap & | vertices () const |
VertexIDMap & | vertices () |
const EdgeSet & | edges () const |
EdgeSet & | edges () |
virtual bool | mergeVertices (Vertex *vBig, Vertex *vSmall, bool erase) |
virtual bool | detachVertex (Vertex *v) |
virtual bool | changeId (Vertex *v, int newId) |
Protected Member Functions | |
void | sortVectorContainers () |
bool | buildIndexMapping (SparseOptimizer::VertexContainer &vlist) |
void | clearIndexMapping () |
Protected Attributes | |
bool * | _forceStopFlag |
bool | _verbose |
VertexContainer | _ivMap |
VertexContainer | _activeVertices |
sorted according to VertexIDCompare More... | |
EdgeContainer | _activeEdges |
sorted according to EdgeIDCompare More... | |
OptimizationAlgorithm * | _algorithm |
BatchStatisticsContainer | _batchStatistics |
global statistics of the optimizer, e.g., timing, num-non-zeros More... | |
bool | _computeBatchStatistics |
Protected Attributes inherited from g2o::OptimizableGraph | |
std::map< std::string, std::string > | _renamedTypesLookup |
long long | _nextEdgeId |
std::vector< HyperGraphActionSet > | _graphActions |
bool | _edge_has_id |
ParameterContainer | _parameters |
JacobianWorkspace | _jacobianWorkspace |
Protected Attributes inherited from g2o::HyperGraph | |
VertexIDMap | _vertices |
EdgeSet | _edges |
Friends | |
class | ActivePathCostFunction |
Additional Inherited Members | |
Static Public Member Functions inherited from g2o::OptimizableGraph | |
static bool | initMultiThreading () |
Public Attributes inherited from g2o::OptimizableGraph | |
class G2O_CORE_API | Vertex |
class G2O_CORE_API | Edge |
Public Attributes inherited from g2o::HyperGraph | |
class G2O_CORE_API | Data |
class G2O_CORE_API | DataContainer |
class G2O_CORE_API | Vertex |
class G2O_CORE_API | Edge |
Static Public Attributes inherited from g2o::HyperGraph | |
static const int | UnassignedId = -1 |
static const int | InvalidId = -2 |
Definition at line 46 of file sparse_optimizer.h.
anonymous enum |
g2o::SparseOptimizer::SparseOptimizer | ( | ) |
Definition at line 50 of file sparse_optimizer.cpp.
References g2o::OptimizableGraph::_graphActions, and AT_NUM_ELEMENTS.
|
virtual |
Definition at line 56 of file sparse_optimizer.cpp.
References _algorithm, and g2o::G2OBatchStatistics::setGlobalStats().
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.
References _activeEdges, and g2o::OptimizableGraph::Edge::chi2().
Referenced by computeInitialGuess(), g2o::computeSimpleStars(), main(), and g2o::SparseOptimizerOnline::optimize().
|
inline |
the edges active in the current optimization
Definition at line 196 of file sparse_optimizer.h.
Referenced by g2o::activeVertexChi(), g2o::BlockSolver< Traits >::buildStructure(), g2o::BlockSolver< Traits >::buildSystem(), g2o::EstimatePropagatorCost::operator()(), g2o::EstimatePropagatorCostOdometry::operator()(), and g2o::SolverSLAM2DLinear::solveOrientation().
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.
References _activeEdges, g2o::OptimizableGraph::Edge::chi2(), g2o::RobustKernel::robustify(), and g2o::OptimizableGraph::Edge::robustKernel().
Referenced by g2o::SparseOptimizerTerminateAction::operator()(), optimize(), g2o::OptimizationAlgorithmLevenberg::solve(), and g2o::OptimizationAlgorithmDogleg::solve().
|
inline |
the vertices active in the current optimization
Definition at line 194 of file sparse_optimizer.h.
Referenced by g2o::OptimizationAlgorithmWithHessian::init(), g2o::StructureOnlySolver< PointDoF >::init(), g2o::Star::labelStarEdges(), main(), and testMarginals().
bool g2o::SparseOptimizer::addComputeErrorAction | ( | HyperGraphAction * | action | ) |
add an action to be executed before the error vectors are computed
Definition at line 598 of file sparse_optimizer.cpp.
References g2o::OptimizableGraph::_graphActions, and AT_COMPUTEACTIVERROR.
|
inline |
the solver used by the optimizer
Definition at line 218 of file sparse_optimizer.h.
Referenced by setAlgorithm().
|
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 272 of file sparse_optimizer.h.
Referenced by main().
|
inline |
returns the set of batch statistics about the optimisation
Definition at line 276 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.
References _ivMap, g2o::OptimizableGraph::Vertex::fixed(), g2o::OptimizableGraph::Vertex::marginalized(), and g2o::OptimizableGraph::Vertex::setHessianIndex().
Referenced by initializeOptimization().
|
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 498 of file sparse_optimizer.cpp.
References _activeEdges, _activeVertices, _ivMap, and g2o::HyperGraph::clear().
Referenced by main(), and g2o::Gm2dlIO::readGm2dl().
|
protected |
Definition at line 192 of file sparse_optimizer.cpp.
References _ivMap.
Referenced by initializeOptimization(), and removeVertex().
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.
References _activeEdges, g2o::OptimizableGraph::_graphActions, actions, g2o::arrayHasNaN(), AT_COMPUTEACTIVERROR, g2o::OptimizableGraph::Edge::computeError(), g2o::OptimizableGraph::Edge::dimension(), and g2o::OptimizableGraph::Edge::errorData().
Referenced by computeInitialGuess(), g2o::computeSimpleStars(), g2o::Star::labelStarEdges(), main(), g2o::SparseOptimizerOnline::optimize(), optimize(), g2o::OptimizationAlgorithmLevenberg::solve(), g2o::OptimizationAlgorithmGaussNewton::solve(), and g2o::OptimizationAlgorithmDogleg::solve().
|
inline |
Definition at line 280 of file sparse_optimizer.h.
Referenced by setComputeBatchStatistics().
|
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 308 of file sparse_optimizer.cpp.
Referenced by g2o::computeSimpleStars(), g2o::Star::labelStarEdges(), and main().
|
virtual |
Same as above but using a specific propagator
Definition at line 314 of file sparse_optimizer.cpp.
References _activeEdges, activeChi2(), computeActiveErrors(), g2o::HyperGraph::Vertex::edges(), g2o::OptimizableGraph::Vertex::fixed(), g2o::OptimizableGraph::Vertex::hessianIndex(), g2o::OptimizableGraph::Edge::initialEstimate(), g2o::OptimizableGraph::Edge::initialEstimatePossible(), g2o::EstimatePropagatorCost::name(), g2o::EstimatePropagator::propagate(), g2o::OptimizableGraph::Vertex::push(), verbose(), g2o::HyperGraph::Edge::vertex(), and g2o::HyperGraph::Edge::vertices().
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 579 of file sparse_optimizer.cpp.
References _algorithm, and g2o::OptimizationAlgorithm::computeMarginals().
Referenced by main(), and testMarginals().
|
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 139 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 154 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 559 of file sparse_optimizer.cpp.
Referenced by g2o::OptimizationAlgorithmLevenberg::solve(), and g2o::OptimizationAlgorithmDogleg::solve().
|
virtual |
same as above, but for the active vertices
Reimplemented from g2o::OptimizableGraph.
Definition at line 619 of file sparse_optimizer.cpp.
References _activeVertices.
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 515 of file sparse_optimizer.cpp.
References _activeEdges.
Referenced by g2o::activeVertexChi(), g2o::EstimatePropagatorCost::operator()(), and g2o::EstimatePropagatorCostOdometry::operator()().
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 505 of file sparse_optimizer.cpp.
References _activeVertices.
|
virtual |
finds a gauge in the graph to remove the undefined dof.
Definition at line 116 of file sparse_optimizer.cpp.
References g2o::OptimizableGraph::Vertex::dimension(), and g2o::HyperGraph::vertices().
Referenced by main().
|
inline |
Definition at line 186 of file sparse_optimizer.h.
Referenced by g2o::SparseOptimizerTerminateAction::setOptimizerStopFlag().
bool g2o::SparseOptimizer::gaugeFreedom | ( | ) |
Definition at line 137 of file sparse_optimizer.cpp.
References g2o::OptimizableGraph::Vertex::dimension(), g2o::OptimizableGraph::Edge::dimension(), g2o::HyperGraph::Vertex::edges(), g2o::OptimizableGraph::Vertex::fixed(), g2o::HyperGraph::Edge::vertices(), and g2o::HyperGraph::vertices().
Referenced by main().
|
inline |
the index mapping of the vertices
Definition at line 192 of file sparse_optimizer.h.
Referenced by g2o::BlockSolver< Traits >::buildStructure(), g2o::BlockSolver< Traits >::buildSystem(), g2o::OptimizationAlgorithmLevenberg::computeLambdaInit(), g2o::Star::labelStarEdges(), g2o::SparseOptimizerOnline::optimize(), and g2o::SolverSLAM2DLinear::solveOrientation().
|
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 272 of file sparse_optimizer.cpp.
References _activeEdges, _activeVertices, g2o::OptimizableGraph::_jacobianWorkspace, g2o::JacobianWorkspace::allocate(), buildIndexMapping(), clearIndexMapping(), g2o::HyperGraph::Edge::numUndefinedVertices(), g2o::OptimizableGraph::postIteration(), g2o::OptimizableGraph::preIteration(), sortVectorContainers(), and g2o::HyperGraph::Edge::vertices().
Referenced by g2o::computeSimpleStars(), initializeOptimization(), g2o::Star::labelStarEdges(), main(), and g2o::G2oSlamInterface::solve().
|
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.
References __PRETTY_FUNCTION__, _activeEdges, _activeVertices, g2o::OptimizableGraph::_jacobianWorkspace, g2o::JacobianWorkspace::allocate(), g2o::OptimizableGraph::Edge::allVerticesFixed(), g2o::arrayHasNaN(), buildIndexMapping(), clearIndexMapping(), g2o::HyperGraph::Vertex::edges(), g2o::HyperGraph::edges(), g2o::OptimizableGraph::Vertex::estimateDimension(), g2o::OptimizableGraph::Vertex::getEstimateData(), g2o::HyperGraph::Vertex::id(), g2o::OptimizableGraph::postIteration(), g2o::OptimizableGraph::preIteration(), sortVectorContainers(), and g2o::HyperGraph::Edge::vertices().
|
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.
References initializeOptimization(), and g2o::HyperGraph::vertices().
|
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::SparseOptimizerOnline, and g2o::SparseOptimizerIncremental.
Definition at line 364 of file sparse_optimizer.cpp.
References __PRETTY_FUNCTION__, _activeEdges, _activeVertices, _algorithm, _batchStatistics, _computeBatchStatistics, _ivMap, activeRobustChi2(), g2o::arrayHasNaN(), computeActiveErrors(), g2o::OptimizableGraph::Vertex::dimension(), g2o::get_monotonic_time(), g2o::HyperGraph::Vertex::id(), g2o::OptimizationAlgorithm::init(), g2o::G2OBatchStatistics::iteration, g2o::G2OBatchStatistics::numEdges, g2o::G2OBatchStatistics::numVertices, OK, g2o::OptimizableGraph::Vertex::oplus(), g2o::OptimizableGraph::postIteration(), g2o::OptimizableGraph::preIteration(), g2o::OptimizationAlgorithm::printVerbose(), g2o::G2OBatchStatistics::setGlobalStats(), g2o::OptimizationAlgorithm::solve(), terminate(), and verbose().
Referenced by g2o::computeSimpleStars(), g2o::Star::labelStarEdges(), and main().
void g2o::SparseOptimizer::pop | ( | SparseOptimizer::VertexContainer & | vlist | ) |
pop (restore) the estimate a subset of the variables from the stack
Definition at line 531 of file sparse_optimizer.cpp.
Referenced by g2o::computeSimpleStars(), g2o::OptimizationAlgorithmLevenberg::solve(), and g2o::OptimizationAlgorithmDogleg::solve().
|
virtual |
pop (restore) the estimate a subset of the variables from the stack
Reimplemented from g2o::OptimizableGraph.
Definition at line 548 of file sparse_optimizer.cpp.
References g2o::OptimizableGraph::Vertex::pop().
|
virtual |
pop (restore) the estimate of the active vertices from the stack
Reimplemented from g2o::OptimizableGraph.
Definition at line 614 of file sparse_optimizer.cpp.
References _activeVertices.
void g2o::SparseOptimizer::push | ( | SparseOptimizer::VertexContainer & | vlist | ) |
push the estimate of a subset of the variables onto a stack
Definition at line 525 of file sparse_optimizer.cpp.
Referenced by g2o::computeSimpleStars(), g2o::OptimizationAlgorithmLevenberg::solve(), and g2o::OptimizationAlgorithmDogleg::solve().
|
virtual |
push the estimate of a subset of the variables onto a stack
Reimplemented from g2o::OptimizableGraph.
Definition at line 537 of file sparse_optimizer.cpp.
References g2o::OptimizableGraph::Vertex::push().
|
virtual |
push all the active vertices onto a stack
Reimplemented from g2o::OptimizableGraph.
Definition at line 609 of file sparse_optimizer.cpp.
References _activeVertices.
bool g2o::SparseOptimizer::removeComputeErrorAction | ( | HyperGraphAction * | action | ) |
remove an action that should no longer be execured before computing the error vectors
Definition at line 604 of file sparse_optimizer.cpp.
References g2o::OptimizableGraph::_graphActions, and AT_COMPUTEACTIVERROR.
|
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 588 of file sparse_optimizer.cpp.
References _ivMap, clearIndexMapping(), g2o::OptimizableGraph::Vertex::hessianIndex(), and g2o::HyperGraph::removeVertex().
void g2o::SparseOptimizer::setAlgorithm | ( | OptimizationAlgorithm * | algorithm | ) |
Definition at line 570 of file sparse_optimizer.cpp.
References _algorithm, algorithm(), and g2o::OptimizationAlgorithm::setOptimizer().
Referenced by g2o::allocateSolverForSclam(), g2o::SparseOptimizerOnline::initSolver(), and main().
void g2o::SparseOptimizer::setComputeBatchStatistics | ( | bool | computeBatchStatistics | ) |
Definition at line 446 of file sparse_optimizer.cpp.
References _batchStatistics, _computeBatchStatistics, computeBatchStatistics(), and g2o::G2OBatchStatistics::setGlobalStats().
Referenced by main().
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 583 of file sparse_optimizer.cpp.
References _forceStopFlag.
Referenced by main().
|
virtual |
sets all vertices to their origin.
Definition at line 301 of file sparse_optimizer.cpp.
References g2o::OptimizableGraph::Vertex::setToOrigin(), and g2o::HyperGraph::vertices().
void g2o::SparseOptimizer::setVerbose | ( | bool | verbose | ) |
Definition at line 565 of file sparse_optimizer.cpp.
References _verbose, and verbose().
Referenced by main().
|
inline |
Definition at line 219 of file sparse_optimizer.h.
References g2o::OptimizableGraph::discardTop(), and G2O_ATTRIBUTE_DEPRECATED.
Referenced by g2o::computeSimpleStars(), g2o::SparseOptimizerOnline::initSolver(), g2o::Star::labelStarEdges(), main(), and g2o::SparseOptimizerOnline::optimize().
|
protected |
Definition at line 491 of file sparse_optimizer.cpp.
References _activeEdges, and _activeVertices.
Referenced by initializeOptimization().
|
inline |
if external stop flag is given, return its state. False otherwise
Definition at line 189 of file sparse_optimizer.h.
Referenced by optimize(), and g2o::OptimizationAlgorithmLevenberg::solve().
|
virtual |
HACK updating the internal structures for online processing
Reimplemented in g2o::SparseOptimizerOnline, and g2o::SparseOptimizerIncremental.
Definition at line 455 of file sparse_optimizer.cpp.
References _activeEdges, _activeVertices, _algorithm, _ivMap, g2o::OptimizableGraph::Edge::allVerticesFixed(), g2o::OptimizableGraph::Vertex::fixed(), g2o::OptimizableGraph::Vertex::marginalized(), g2o::OptimizableGraph::Vertex::setHessianIndex(), and g2o::OptimizationAlgorithm::updateStructure().
Referenced by main(), and g2o::SparseOptimizerOnline::updateInitialization().
|
inline |
verbose information during optimization
Definition at line 179 of file sparse_optimizer.h.
Referenced by computeInitialGuess(), main(), g2o::SparseOptimizerOnline::optimize(), optimize(), and setVerbose().
|
friend |
Definition at line 54 of file sparse_optimizer.h.
|
protected |
sorted according to EdgeIDCompare
Definition at line 296 of file sparse_optimizer.h.
Referenced by activeChi2(), activeRobustChi2(), clear(), computeActiveErrors(), computeInitialGuess(), findActiveEdge(), initializeOptimization(), g2o::SparseOptimizerOnline::optimize(), optimize(), sortVectorContainers(), and updateInitialization().
|
protected |
sorted according to VertexIDCompare
Definition at line 295 of file sparse_optimizer.h.
Referenced by clear(), discardTop(), findActiveVertex(), initializeOptimization(), optimize(), pop(), push(), sortVectorContainers(), and updateInitialization().
|
protected |
Definition at line 300 of file sparse_optimizer.h.
Referenced by computeMarginals(), g2o::SparseOptimizerOnline::optimize(), optimize(), setAlgorithm(), updateInitialization(), and ~SparseOptimizer().
|
protected |
global statistics of the optimizer, e.g., timing, num-non-zeros
Definition at line 308 of file sparse_optimizer.h.
Referenced by optimize(), and setComputeBatchStatistics().
|
protected |
Definition at line 309 of file sparse_optimizer.h.
Referenced by optimize(), and setComputeBatchStatistics().
|
protected |
Definition at line 291 of file sparse_optimizer.h.
Referenced by setForceStopFlag().
|
protected |
Definition at line 294 of file sparse_optimizer.h.
Referenced by buildIndexMapping(), clear(), clearIndexMapping(), optimize(), removeVertex(), g2o::SparseOptimizerOnline::update(), and updateInitialization().
|
protected |
Definition at line 292 of file sparse_optimizer.h.
Referenced by setVerbose().