#include <graph_optimizer_sparse.h>
Definition at line 35 of file graph_optimizer_sparse.h.
Definition at line 37 of file graph_optimizer_sparse.h.
Definition at line 39 of file graph_optimizer_sparse.cpp.
g2o::SparseOptimizer::~SparseOptimizer | ( | ) | [virtual] |
Definition at line 54 of file graph_optimizer_sparse.cpp.
double g2o::SparseOptimizer::activeChi2 | ( | ) | const |
Returns the cached chi2 of the active portion of the graph
Definition at line 76 of file graph_optimizer_sparse.cpp.
const EdgeContainer& g2o::SparseOptimizer::activeEdges | ( | ) | const [inline] |
The edges active in the current optimization
Definition at line 177 of file graph_optimizer_sparse.h.
const VertexContainer& g2o::SparseOptimizer::activeVertices | ( | ) | const [inline] |
The vertices active in the current optimization
Definition at line 172 of file graph_optimizer_sparse.h.
bool g2o::SparseOptimizer::buildIndexMapping | ( | SparseOptimizer::VertexContainer & | vlist | ) | [protected] |
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.
void g2o::SparseOptimizer::clearIndexMapping | ( | ) | [protected] |
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.
void g2o::SparseOptimizer::computeInitialGuess | ( | ) | [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 utilizing a cost-function specified.
costFunction,: | the cost function used maxDistance: the distance where to stop the search |
Definition at line 373 of file graph_optimizer_sparse.cpp.
double g2o::SparseOptimizer::computeLambdaInit | ( | ) | [protected] |
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
blockIndices,: | the pattern |
spinv,: | the sparse block matrix with the result |
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.
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 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.
OptimizableGraph::Vertex * g2o::SparseOptimizer::findGauge | ( | ) | [virtual] |
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.
const VertexContainer& g2o::SparseOptimizer::indexMapping | ( | ) | const [inline] |
The index mapping of the vertices
Definition at line 167 of file graph_optimizer_sparse.h.
bool g2o::SparseOptimizer::initializeOptimization | ( | HyperGraph::EdgeSet & | eset | ) | [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 schurr complement or to set as fixed during the optimization.
eset,: | the subgraph to be optimized. |
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.
vset,: | the subgraph to be optimized. |
level,: | is the level (in multilevel optimization) |
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.
level,: | is the level (in multilevel optimization) |
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.
int g2o::SparseOptimizer::maxTrialsAfterFailure | ( | ) | const [inline] |
Get the number of inner iterations for Levenberg-Marquardt
Definition at line 277 of file graph_optimizer_sparse.h.
Method g2o::SparseOptimizer::method | ( | ) | const [inline] |
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.
void g2o::SparseOptimizer::pop | ( | SparseOptimizer::VertexContainer & | vlist | ) |
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.
void g2o::SparseOptimizer::push | ( | SparseOptimizer::VertexContainer & | vlist | ) |
Push the estimate of a subset of the variables onto a stack
Definition at line 777 of file graph_optimizer_sparse.cpp.
void g2o::SparseOptimizer::push | ( | HyperGraph::VertexSet & | vlist | ) | [virtual] |
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.
bool g2o::SparseOptimizer::removeVertex | ( | Vertex * | v | ) | [virtual] |
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.
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 876 of file graph_optimizer_sparse.cpp.
void g2o::SparseOptimizer::setMaxTrialsAfterFailure | ( | int | max_trials | ) |
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.
void g2o::SparseOptimizer::setMethod | ( | SparseOptimizer::Method | method | ) |
Definition at line 835 of file graph_optimizer_sparse.cpp.
void g2o::SparseOptimizer::setSolver | ( | Solver * | solver | ) |
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.
void g2o::SparseOptimizer::setVerbose | ( | bool | verbose | ) |
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.
Solver* g2o::SparseOptimizer::solver | ( | ) | [inline] |
Definition at line 199 of file graph_optimizer_sparse.h.
void g2o::SparseOptimizer::sortVectorContainers | ( | ) | [protected] |
Definition at line 735 of file graph_optimizer_sparse.cpp.
bool g2o::SparseOptimizer::terminate | ( | ) | [inline] |
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
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.
bool g2o::SparseOptimizer::updateInitialization | ( | HyperGraph::VertexSet & | vset, |
HyperGraph::EdgeSet & | eset | ||
) | [virtual] |
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.
double g2o::SparseOptimizer::userLambdaInit | ( | ) | [inline] |
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.
friend class ActivePathCostFunction [friend] |
Definition at line 39 of file graph_optimizer_sparse.h.
EdgeContainer g2o::SparseOptimizer::_activeEdges [protected] |
sorted according to EdgeIDCompare
Definition at line 289 of file graph_optimizer_sparse.h.
VertexContainer g2o::SparseOptimizer::_activeVertices [protected] |
sorted according to VertexIDCompare
Definition at line 288 of file graph_optimizer_sparse.h.
double g2o::SparseOptimizer::_currentLambda [protected] |
Definition at line 284 of file graph_optimizer_sparse.h.
bool* g2o::SparseOptimizer::_forceStopFlag [protected] |
Definition at line 280 of file graph_optimizer_sparse.h.
double g2o::SparseOptimizer::_goodStepLowerScale [protected] |
lower bound for lambda decrease if a good LM step
Definition at line 299 of file graph_optimizer_sparse.h.
double g2o::SparseOptimizer::_goodStepUpperScale [protected] |
upper bound for lambda decrease if a good LM step
Definition at line 301 of file graph_optimizer_sparse.h.
VertexContainer g2o::SparseOptimizer::_ivMap [protected] |
Definition at line 287 of file graph_optimizer_sparse.h.
int g2o::SparseOptimizer::_maxTrialsAfterFailure [protected] |
Definition at line 285 of file graph_optimizer_sparse.h.
Method g2o::SparseOptimizer::_method [protected] |
Definition at line 283 of file graph_optimizer_sparse.h.
Solver* g2o::SparseOptimizer::_solver [protected] |
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.
double g2o::SparseOptimizer::_userLambdaInit [protected] |
Definition at line 297 of file graph_optimizer_sparse.h.
bool g2o::SparseOptimizer::_verbose [protected] |
Definition at line 281 of file graph_optimizer_sparse.h.