g2o
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
g2o::SparseOptimizer Class Reference

#include <sparse_optimizer.h>

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

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 VertexfindGauge ()
 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 VertexContainerindexMapping () const
 the index mapping of the vertices More...
 
const VertexContaineractiveVertices () const
 the vertices active in the current optimization More...
 
const EdgeContaineractiveEdges () 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 OptimizationAlgorithmalgorithm () const
 the solver used by the optimizer More...
 
OptimizationAlgorithmsolver ()
 
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 BatchStatisticsContainerbatchStatistics () const
 
BatchStatisticsContainerbatchStatistics ()
 
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
Vertexvertex (int id)
 returns the vertex number id appropriately casted More...
 
const Vertexvertex (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)
 
Parameterparameter (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
 
JacobianWorkspacejacobianWorkspace ()
 the workspace for storing the Jacobians of the graph More...
 
const JacobianWorkspacejacobianWorkspace () const
 
ParameterContainerparameters ()
 
const ParameterContainerparameters () 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...
 
Vertexvertex (int id)
 returns a vertex id in the hyper-graph, or 0 if the vertex id is not present More...
 
const Vertexvertex (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 VertexIDMapvertices () const
 
VertexIDMapvertices ()
 
const EdgeSetedges () const
 
EdgeSetedges ()
 
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
 

Detailed Description

Definition at line 46 of file sparse_optimizer.h.

Member Enumeration Documentation

anonymous enum

Constructor & Destructor Documentation

g2o::SparseOptimizer::SparseOptimizer ( )

Definition at line 50 of file sparse_optimizer.cpp.

References g2o::OptimizableGraph::_graphActions, and AT_NUM_ELEMENTS.

50  :
52  {
54  }
std::vector< HyperGraphActionSet > _graphActions
OptimizationAlgorithm * _algorithm
g2o::SparseOptimizer::~SparseOptimizer ( )
virtual

Definition at line 56 of file sparse_optimizer.cpp.

References _algorithm, and g2o::G2OBatchStatistics::setGlobalStats().

56  {
57  delete _algorithm;
59  }
static void setGlobalStats(G2OBatchStatistics *b)
Definition: batch_stats.cpp:85
OptimizationAlgorithm * _algorithm

Member Function Documentation

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().

91  {
92  double chi = 0.0;
93  for (EdgeContainer::const_iterator it = _activeEdges.begin(); it != _activeEdges.end(); ++it) {
94  const OptimizableGraph::Edge* e = *it;
95  chi += e->chi2();
96  }
97  return chi;
98  }
class G2O_CORE_API Edge
EdgeContainer _activeEdges
sorted according to EdgeIDCompare
const EdgeContainer& g2o::SparseOptimizer::activeEdges ( ) const
inline
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().

101  {
102  Vector3D rho;
103  double chi = 0.0;
104  for (EdgeContainer::const_iterator it = _activeEdges.begin(); it != _activeEdges.end(); ++it) {
105  const OptimizableGraph::Edge* e = *it;
106  if (e->robustKernel()) {
107  e->robustKernel()->robustify(e->chi2(), rho);
108  chi += rho[0];
109  }
110  else
111  chi += e->chi2();
112  }
113  return chi;
114  }
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
class G2O_CORE_API Edge
EdgeContainer _activeEdges
sorted according to EdgeIDCompare
const VertexContainer& g2o::SparseOptimizer::activeVertices ( ) const
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().

194 { return _activeVertices;}
VertexContainer _activeVertices
sorted according to VertexIDCompare
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.

599  {
600  std::pair<HyperGraphActionSet::iterator, bool> insertResult = _graphActions[AT_COMPUTEACTIVERROR].insert(action);
601  return insertResult.second;
602  }
std::vector< HyperGraphActionSet > _graphActions
const OptimizationAlgorithm* g2o::SparseOptimizer::algorithm ( ) const
inline

the solver used by the optimizer

Definition at line 218 of file sparse_optimizer.h.

Referenced by setAlgorithm().

218 { return _algorithm;}
OptimizationAlgorithm * _algorithm
const BatchStatisticsContainer& g2o::SparseOptimizer::batchStatistics ( ) const
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().

272 { return _batchStatistics;}
BatchStatisticsContainer _batchStatistics
global statistics of the optimizer, e.g., timing, num-non-zeros
BatchStatisticsContainer& g2o::SparseOptimizer::batchStatistics ( )
inline

returns the set of batch statistics about the optimisation

Definition at line 276 of file sparse_optimizer.h.

276 { return _batchStatistics;}
BatchStatisticsContainer _batchStatistics
global statistics of the optimizer, e.g., timing, num-non-zeros
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 166 of file sparse_optimizer.cpp.

References _ivMap, g2o::OptimizableGraph::Vertex::fixed(), g2o::OptimizableGraph::Vertex::marginalized(), and g2o::OptimizableGraph::Vertex::setHessianIndex().

Referenced by initializeOptimization().

166  {
167  if (! vlist.size()){
168  _ivMap.clear();
169  return false;
170  }
171 
172  _ivMap.resize(vlist.size());
173  size_t i = 0;
174  for (int k=0; k<2; k++)
175  for (VertexContainer::iterator it=vlist.begin(); it!=vlist.end(); ++it){
176  OptimizableGraph::Vertex* v = *it;
177  if (! v->fixed()){
178  if (static_cast<int>(v->marginalized()) == k){
179  v->setHessianIndex(i);
180  _ivMap[i]=v;
181  i++;
182  }
183  }
184  else {
185  v->setHessianIndex(-1);
186  }
187  }
188  _ivMap.resize(i);
189  return true;
190  }
VertexContainer _ivMap
class G2O_CORE_API Vertex
void g2o::SparseOptimizer::clear ( )
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().

498  {
499  _ivMap.clear();
500  _activeVertices.clear();
501  _activeEdges.clear();
503  }
VertexContainer _ivMap
VertexContainer _activeVertices
sorted according to VertexIDCompare
EdgeContainer _activeEdges
sorted according to EdgeIDCompare
virtual void clear()
clears the graph and empties all structures.
void g2o::SparseOptimizer::clearIndexMapping ( )
protected

Definition at line 192 of file sparse_optimizer.cpp.

References _ivMap.

Referenced by initializeOptimization(), and removeVertex().

192  {
193  for (size_t i=0; i<_ivMap.size(); ++i){
194  _ivMap[i]->setHessianIndex(-1);
195  _ivMap[i]=0;
196  }
197  }
VertexContainer _ivMap
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().

62  {
63  // call the callbacks in case there is something registered
65  if (actions.size() > 0) {
66  for (HyperGraphActionSet::iterator it = actions.begin(); it != actions.end(); ++it)
67  (*(*it))(this);
68  }
69 
70 # ifdef G2O_OPENMP
71 # pragma omp parallel for default (shared) if (_activeEdges.size() > 50)
72 # endif
73  for (int k = 0; k < static_cast<int>(_activeEdges.size()); ++k) {
75  e->computeError();
76  }
77 
78 # ifndef NDEBUG
79  for (int k = 0; k < static_cast<int>(_activeEdges.size()); ++k) {
81  bool hasNan = arrayHasNaN(e->errorData(), e->dimension());
82  if (hasNan) {
83  cerr << "computeActiveErrors(): found NaN in error for edge " << e << endl;
84  }
85  }
86 # endif
87 
88  }
bool arrayHasNaN(const double *array, int size, int *nanIndex=0)
Definition: misc.h:177
class G2O_CORE_API Edge
EdgeContainer _activeEdges
sorted according to EdgeIDCompare
Protocol The SLAM executable accepts actions
Definition: protocol.txt:3
std::set< HyperGraphAction * > HyperGraphActionSet
std::vector< HyperGraphActionSet > _graphActions
bool g2o::SparseOptimizer::computeBatchStatistics ( ) const
inline

Definition at line 280 of file sparse_optimizer.h.

Referenced by setComputeBatchStatistics().

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 utlizing a cost-function specified.

Parameters
costFunctionthe 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().

309  {
310  EstimatePropagator::PropagateCost costFunction(this);
311  computeInitialGuess(costFunction);
312  }
virtual void computeInitialGuess()
EstimatePropagatorCost PropagateCost
void g2o::SparseOptimizer::computeInitialGuess ( EstimatePropagatorCost propagator)
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().

315  {
317  std::set<Vertex*> backupVertices;
318  HyperGraph::VertexSet fixedVertices; // these are the root nodes where to start the initialization
319  for (EdgeContainer::iterator it = _activeEdges.begin(); it != _activeEdges.end(); ++it) {
320  OptimizableGraph::Edge* e = *it;
321  for (size_t i = 0; i < e->vertices().size(); ++i) {
322  OptimizableGraph::Vertex* v = static_cast<OptimizableGraph::Vertex*>(e->vertex(i));
323  if (!v)
324  continue;
325  if (v->fixed())
326  fixedVertices.insert(v);
327  else { // check for having a prior which is able to fully initialize a vertex
328  for (EdgeSet::const_iterator vedgeIt = v->edges().begin(); vedgeIt != v->edges().end(); ++vedgeIt) {
329  OptimizableGraph::Edge* vedge = static_cast<OptimizableGraph::Edge*>(*vedgeIt);
330  if (vedge->vertices().size() == 1 && vedge->initialEstimatePossible(emptySet, v) > 0.) {
331  //cerr << "Initialize with prior for " << v->id() << endl;
332  vedge->initialEstimate(emptySet, v);
333  fixedVertices.insert(v);
334  }
335  }
336  }
337  if (v->hessianIndex() == -1) {
338  std::set<Vertex*>::const_iterator foundIt = backupVertices.find(v);
339  if (foundIt == backupVertices.end()) {
340  v->push();
341  backupVertices.insert(v);
342  }
343  }
344  }
345  }
346 
347  EstimatePropagator estimatePropagator(this);
348  estimatePropagator.propagate(fixedVertices, costFunction);
349 
350  // restoring the vertices that should not be initialized
351  for (std::set<Vertex*>::iterator it = backupVertices.begin(); it != backupVertices.end(); ++it) {
352  Vertex* v = *it;
353  v->pop();
354  }
355  if (verbose()) {
357  cerr << "iteration= -1\t chi2= " << activeChi2()
358  << "\t time= 0.0"
359  << "\t cumTime= 0.0"
360  << "\t (using initial guess from " << costFunction.name() << ")" << endl;
361  }
362  }
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:136
class G2O_CORE_API Vertex
class G2O_CORE_API Edge
EdgeContainer _activeEdges
sorted according to EdgeIDCompare
bool verbose() const
verbose information during optimization
double activeChi2() const
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
blockIndicesthe pattern
spinvthe sparse block matrix with the result
Returns
false if the operation is not supported by the solver

Definition at line 579 of file sparse_optimizer.cpp.

References _algorithm, and g2o::OptimizationAlgorithm::computeMarginals().

Referenced by main(), and testMarginals().

579  {
580  return _algorithm->computeMarginals(spinv, blockIndices);
581  }
OptimizationAlgorithm * _algorithm
virtual bool computeMarginals(SparseBlockMatrix< MatrixXD > &spinv, const std::vector< std::pair< int, int > > &blockIndices)=0
bool g2o::SparseOptimizer::computeMarginals ( SparseBlockMatrix< MatrixXD > &  spinv,
const Vertex vertex 
)
inline

computes the inverse of the specified vertex.

Parameters
vertexthe vertex whose state is to be marginalised
spinvthe sparse block matrix with the result
Returns
false if the operation is not supported by the solver

Definition at line 139 of file sparse_optimizer.h.

139  {
140  if (vertex->hessianIndex() < 0) {
141  return false;
142  }
143  std::vector<std::pair<int, int> > index;
144  index.push_back(std::pair<int, int>(vertex->hessianIndex(), vertex->hessianIndex()));
145  return computeMarginals(spinv, index);
146  }
Vertex * vertex(int id)
returns the vertex number id appropriately casted
bool computeMarginals(SparseBlockMatrix< MatrixXD > &spinv, const std::vector< std::pair< int, int > > &blockIndices)
bool g2o::SparseOptimizer::computeMarginals ( SparseBlockMatrix< MatrixXD > &  spinv,
const VertexContainer vertices 
)
inline

computes the inverse of the set specified vertices, assembled into a single covariance matrix.

Parameters
vertexthe pattern
spinvthe sparse block matrix with the result
Returns
false if the operation is not supported by the solver

Definition at line 154 of file sparse_optimizer.h.

154  {
155  std::vector<std::pair<int, int> > indices;
156  for (VertexContainer::const_iterator it = vertices.begin(); it != vertices.end(); ++it) {
157  indices.push_back(std::pair<int, int>((*it)->hessianIndex(),(*it)->hessianIndex()));
158  }
159  return computeMarginals(spinv, indices);
160  }
const VertexIDMap & vertices() const
Definition: hyper_graph.h:225
bool computeMarginals(SparseBlockMatrix< MatrixXD > &spinv, const std::vector< std::pair< int, int > > &blockIndices)
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().

560  {
561  for (VertexContainer::iterator it = vlist.begin(); it != vlist.end(); ++it)
562  (*it)->discardTop();
563  }
void g2o::SparseOptimizer::discardTop ( )
virtual

same as above, but for the active vertices

Reimplemented from g2o::OptimizableGraph.

Definition at line 619 of file sparse_optimizer.cpp.

References _activeVertices.

620  {
622  }
VertexContainer _activeVertices
sorted according to VertexIDCompare
void discardTop()
same as above, but for the active vertices
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()().

516  {
517  EdgeContainer::const_iterator lower = lower_bound(_activeEdges.begin(), _activeEdges.end(), e, EdgeIDCompare());
518  if (lower == _activeEdges.end())
519  return _activeEdges.end();
520  if ((*lower) == e)
521  return lower;
522  return _activeEdges.end();
523  }
EdgeContainer _activeEdges
sorted according to EdgeIDCompare
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.

506  {
507  VertexContainer::const_iterator lower = lower_bound(_activeVertices.begin(), _activeVertices.end(), v, VertexIDCompare());
508  if (lower == _activeVertices.end())
509  return _activeVertices.end();
510  if ((*lower) == v)
511  return lower;
512  return _activeVertices.end();
513  }
VertexContainer _activeVertices
sorted according to VertexIDCompare
OptimizableGraph::Vertex * g2o::SparseOptimizer::findGauge ( )
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().

116  {
117  if (vertices().empty())
118  return 0;
119 
120  int maxDim=0;
121  for (HyperGraph::VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it){
122  OptimizableGraph::Vertex* v=static_cast<OptimizableGraph::Vertex*>(it->second);
123  maxDim=std::max(maxDim,v->dimension());
124  }
125 
127  for (HyperGraph::VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it){
128  OptimizableGraph::Vertex* v=static_cast<OptimizableGraph::Vertex*>(it->second);
129  if (v->dimension()==maxDim){
130  rut=v;
131  break;
132  }
133  }
134  return rut;
135  }
const VertexIDMap & vertices() const
Definition: hyper_graph.h:225
class G2O_CORE_API Vertex
bool* g2o::SparseOptimizer::forceStopFlag ( ) const
inline
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().

138  {
139  if (vertices().empty())
140  return false;
141 
142  int maxDim=0;
143  for (HyperGraph::VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it){
144  OptimizableGraph::Vertex* v=static_cast<OptimizableGraph::Vertex*>(it->second);
145  maxDim = std::max(maxDim,v->dimension());
146  }
147 
148  for (HyperGraph::VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it){
149  OptimizableGraph::Vertex* v=static_cast<OptimizableGraph::Vertex*>(it->second);
150  if (v->dimension() == maxDim) {
151  // test for fixed vertex
152  if (v->fixed()) {
153  return false;
154  }
155  // test for full dimension prior
156  for (HyperGraph::EdgeSet::const_iterator eit = v->edges().begin(); eit != v->edges().end(); ++eit) {
157  OptimizableGraph::Edge* e = static_cast<OptimizableGraph::Edge*>(*eit);
158  if (e->vertices().size() == 1 && e->dimension() == maxDim)
159  return false;
160  }
161  }
162  }
163  return true;
164  }
const VertexIDMap & vertices() const
Definition: hyper_graph.h:225
class G2O_CORE_API Vertex
class G2O_CORE_API Edge
const VertexContainer& g2o::SparseOptimizer::indexMapping ( ) const
inline
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 schur complement or to set as fixed during the optimization.

Parameters
esetthe subgraph to be optimized.
Returns
false if somethings goes wrong

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().

272  {
273  preIteration(-1);
274  bool workspaceAllocated = _jacobianWorkspace.allocate(); (void) workspaceAllocated;
275  assert(workspaceAllocated && "Error while allocating memory for the Jacobians");
277  _activeVertices.clear();
278  _activeEdges.clear();
279  _activeEdges.reserve(eset.size());
280  set<Vertex*> auxVertexSet; // temporary structure to avoid duplicates
281  for (HyperGraph::EdgeSet::iterator it=eset.begin(); it!=eset.end(); ++it){
283  if (e->numUndefinedVertices())
284  continue;
285  for (vector<HyperGraph::Vertex*>::const_iterator vit = e->vertices().begin(); vit != e->vertices().end(); ++vit) {
286  auxVertexSet.insert(static_cast<OptimizableGraph::Vertex*>(*vit));
287  }
288  _activeEdges.push_back(reinterpret_cast<OptimizableGraph::Edge*>(*it));
289  }
290 
291  _activeVertices.reserve(auxVertexSet.size());
292  for (set<Vertex*>::iterator it = auxVertexSet.begin(); it != auxVertexSet.end(); ++it)
293  _activeVertices.push_back(*it);
294 
296  bool indexMappingStatus = buildIndexMapping(_activeVertices);
297  postIteration(-1);
298  return indexMappingStatus;
299  }
VertexContainer _activeVertices
sorted according to VertexIDCompare
virtual void postIteration(int)
called at the end of an iteration (argument is the number of the iteration)
class G2O_CORE_API Edge
EdgeContainer _activeEdges
sorted according to EdgeIDCompare
bool buildIndexMapping(SparseOptimizer::VertexContainer &vlist)
JacobianWorkspace _jacobianWorkspace
virtual void preIteration(int)
called at the beginning of an iteration (argument is the number of the iteration) ...
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 schur complement or to set as fixed during the optimization.

Parameters
vsetthe subgraph to be optimized.
levelis the level (in multilevel optimization)
Returns
false if somethings goes wrong

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().

206  {
207  if (edges().size() == 0) {
208  cerr << __PRETTY_FUNCTION__ << ": Attempt to initialize an empty graph" << endl;
209  return false;
210  }
211  preIteration(-1);
212  bool workspaceAllocated = _jacobianWorkspace.allocate(); (void) workspaceAllocated;
213  assert(workspaceAllocated && "Error while allocating memory for the Jacobians");
215  _activeVertices.clear();
216  _activeVertices.reserve(vset.size());
217  _activeEdges.clear();
218  set<Edge*> auxEdgeSet; // temporary structure to avoid duplicates
219  for (HyperGraph::VertexSet::iterator it=vset.begin(); it!=vset.end(); ++it){
221  const OptimizableGraph::EdgeSet& vEdges=v->edges();
222  // count if there are edges in that level. If not remove from the pool
223  int levelEdges=0;
224  for (OptimizableGraph::EdgeSet::const_iterator it=vEdges.begin(); it!=vEdges.end(); ++it){
225  OptimizableGraph::Edge* e=reinterpret_cast<OptimizableGraph::Edge*>(*it);
226  if (level < 0 || e->level() == level) {
227 
228  bool allVerticesOK = true;
229  for (vector<HyperGraph::Vertex*>::const_iterator vit = e->vertices().begin(); vit != e->vertices().end(); ++vit) {
230  if (vset.find(*vit) == vset.end()) {
231  allVerticesOK = false;
232  break;
233  }
234  }
235  if (allVerticesOK && !e->allVerticesFixed()) {
236  auxEdgeSet.insert(e);
237  levelEdges++;
238  }
239 
240  }
241  }
242  if (levelEdges){
243  _activeVertices.push_back(v);
244 
245  // test for NANs in the current estimate if we are debugging
246 # ifndef NDEBUG
247  int estimateDim = v->estimateDimension();
248  if (estimateDim > 0) {
249  VectorXD estimateData(estimateDim);
250  if (v->getEstimateData(estimateData.data()) == true) {
251  int k;
252  bool hasNan = arrayHasNaN(estimateData.data(), estimateDim, &k);
253  if (hasNan)
254  cerr << __PRETTY_FUNCTION__ << ": Vertex " << v->id() << " contains a nan entry at index " << k << endl;
255  }
256  }
257 # endif
258 
259  }
260  }
261 
262  _activeEdges.reserve(auxEdgeSet.size());
263  for (set<Edge*>::iterator it = auxEdgeSet.begin(); it != auxEdgeSet.end(); ++it)
264  _activeEdges.push_back(*it);
265 
267  bool indexMappingStatus = buildIndexMapping(_activeVertices);
268  postIteration(-1);
269  return indexMappingStatus;
270  }
#define __PRETTY_FUNCTION__
Definition: macros.h:89
VertexContainer _activeVertices
sorted according to VertexIDCompare
virtual void postIteration(int)
called at the end of an iteration (argument is the number of the iteration)
bool arrayHasNaN(const double *array, int size, int *nanIndex=0)
Definition: misc.h:177
std::set< Edge * > EdgeSet
Definition: hyper_graph.h:135
class G2O_CORE_API Vertex
const EdgeSet & edges() const
Definition: hyper_graph.h:230
class G2O_CORE_API Edge
EdgeContainer _activeEdges
sorted according to EdgeIDCompare
bool buildIndexMapping(SparseOptimizer::VertexContainer &vlist)
Eigen::Matrix< double, Eigen::Dynamic, 1, Eigen::ColMajor > VectorXD
Definition: eigen_types.h:48
JacobianWorkspace _jacobianWorkspace
virtual void preIteration(int)
called at the beginning of an iteration (argument is the number of the iteration) ...
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 schur complement or to set as fixed during the optimization.

Parameters
levelis the level (in multilevel optimization)
Returns
false if somethings goes wrong

Definition at line 199 of file sparse_optimizer.cpp.

References initializeOptimization(), and g2o::HyperGraph::vertices().

199  {
201  for (VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it)
202  vset.insert(it->second);
203  return initializeOptimization(vset,level);
204  }
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:136
const VertexIDMap & vertices() const
Definition: hyper_graph.h:225
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
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::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().

365  {
366  if (_ivMap.size() == 0) {
367  cerr << __PRETTY_FUNCTION__ << ": 0 vertices to optimize, maybe forgot to call initializeOptimization()" << endl;
368  return -1;
369  }
370 
371  int cjIterations=0;
372  double cumTime=0;
373  bool ok=true;
374 
375  ok = _algorithm->init(online);
376  if (! ok) {
377  cerr << __PRETTY_FUNCTION__ << " Error while initializing" << endl;
378  return -1;
379  }
380 
381  _batchStatistics.clear();
383  _batchStatistics.resize(iterations);
384 
385  OptimizationAlgorithm::SolverResult result = OptimizationAlgorithm::OK;
386  for (int i=0; i<iterations && ! terminate() && ok; i++){
387  preIteration(i);
388 
390  G2OBatchStatistics& cstat = _batchStatistics[i];
392  cstat.iteration = i;
393  cstat.numEdges = _activeEdges.size();
394  cstat.numVertices = _activeVertices.size();
395  }
396 
397  double ts = get_monotonic_time();
398  result = _algorithm->solve(i, online);
399  ok = ( result == OptimizationAlgorithm::OK );
400 
401  bool errorComputed = false;
404  errorComputed = true;
406  _batchStatistics[i].timeIteration = get_monotonic_time()-ts;
407  }
408 
409  if (verbose()){
410  double dts = get_monotonic_time()-ts;
411  cumTime += dts;
412  if (! errorComputed)
414  cerr << "iteration= " << i
415  << "\t chi2= " << FIXED(activeRobustChi2())
416  << "\t time= " << dts
417  << "\t cumTime= " << cumTime
418  << "\t edges= " << _activeEdges.size();
419  _algorithm->printVerbose(cerr);
420  cerr << endl;
421  }
422  ++cjIterations;
423  postIteration(i);
424  }
425  if (result == OptimizationAlgorithm::Fail) {
426  return 0;
427  }
428  return cjIterations;
429  }
virtual void printVerbose(std::ostream &os) const
double get_monotonic_time()
Definition: timeutil.cpp:113
virtual SolverResult solve(int iteration, bool online=false)=0
VertexContainer _ivMap
bool terminate()
if external stop flag is given, return its state. False otherwise
#define __PRETTY_FUNCTION__
Definition: macros.h:89
VertexContainer _activeVertices
sorted according to VertexIDCompare
virtual bool init(bool online=false)=0
virtual void postIteration(int)
called at the end of an iteration (argument is the number of the iteration)
BatchStatisticsContainer _batchStatistics
global statistics of the optimizer, e.g., timing, num-non-zeros
EdgeContainer _activeEdges
sorted according to EdgeIDCompare
double activeRobustChi2() const
virtual void preIteration(int)
called at the beginning of an iteration (argument is the number of the iteration) ...
bool verbose() const
verbose information during optimization
static void setGlobalStats(G2OBatchStatistics *b)
Definition: batch_stats.cpp:85
OptimizationAlgorithm * _algorithm
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().

532  {
533  for (VertexContainer::iterator it = vlist.begin(); it != vlist.end(); ++it)
534  (*it)->pop();
535  }
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 548 of file sparse_optimizer.cpp.

References g2o::OptimizableGraph::Vertex::pop().

549  {
550  for (HyperGraph::VertexSet::iterator it = vlist.begin(); it != vlist.end(); ++it){
551  OptimizableGraph::Vertex* v = dynamic_cast<OptimizableGraph::Vertex*> (*it);
552  if (v)
553  v->pop();
554  else
555  cerr << __FUNCTION__ << ": FATAL POP SET" << endl;
556  }
557  }
class G2O_CORE_API Vertex
void g2o::SparseOptimizer::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.

615  {
617  }
VertexContainer _activeVertices
sorted according to VertexIDCompare
void pop()
pop (restore) the estimate of the active vertices from the stack
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().

526  {
527  for (VertexContainer::iterator it = vlist.begin(); it != vlist.end(); ++it)
528  (*it)->push();
529  }
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 537 of file sparse_optimizer.cpp.

References g2o::OptimizableGraph::Vertex::push().

538  {
539  for (HyperGraph::VertexSet::iterator it = vlist.begin(); it != vlist.end(); ++it) {
540  OptimizableGraph::Vertex* v = dynamic_cast<OptimizableGraph::Vertex*>(*it);
541  if (v)
542  v->push();
543  else
544  cerr << __FUNCTION__ << ": FATAL PUSH SET" << endl;
545  }
546  }
class G2O_CORE_API Vertex
void g2o::SparseOptimizer::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.

610  {
612  }
VertexContainer _activeVertices
sorted according to VertexIDCompare
void push()
push all the active vertices onto a stack
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.

605  {
606  return _graphActions[AT_COMPUTEACTIVERROR].erase(action) > 0;
607  }
std::vector< HyperGraphActionSet > _graphActions
bool g2o::SparseOptimizer::removeVertex ( HyperGraph::Vertex v,
bool  detach = false 
)
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().

589  {
590  OptimizableGraph::Vertex* vv = static_cast<OptimizableGraph::Vertex*>(v);
591  if (vv->hessianIndex() >= 0) {
593  _ivMap.clear();
594  }
595  return HyperGraph::removeVertex(v, detach);
596  }
VertexContainer _ivMap
virtual bool removeVertex(Vertex *v, bool detach=false)
removes a vertex from the graph. Returns true on success (vertex was present)
class G2O_CORE_API Vertex
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().

571  {
572  if (_algorithm) // reset the optimizer for the formerly used solver
575  if (_algorithm)
576  _algorithm->setOptimizer(this);
577  }
void setOptimizer(SparseOptimizer *optimizer)
const OptimizationAlgorithm * algorithm() const
the solver used by the optimizer
OptimizationAlgorithm * _algorithm
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().

447  {
448  if ((_computeBatchStatistics == true) && (computeBatchStatistics == false)) {
450  _batchStatistics.clear();
451  }
453  }
BatchStatisticsContainer _batchStatistics
global statistics of the optimizer, e.g., timing, num-non-zeros
bool computeBatchStatistics() const
static void setGlobalStats(G2OBatchStatistics *b)
Definition: batch_stats.cpp:85
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().

584  {
585  _forceStopFlag=flag;
586  }
void g2o::SparseOptimizer::setToOrigin ( )
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().

301  {
302  for (VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it) {
303  OptimizableGraph::Vertex* v = static_cast<OptimizableGraph::Vertex*>(it->second);
304  v->setToOrigin();
305  }
306  }
const VertexIDMap & vertices() const
Definition: hyper_graph.h:225
class G2O_CORE_API Vertex
void g2o::SparseOptimizer::setVerbose ( bool  verbose)

Definition at line 565 of file sparse_optimizer.cpp.

References _verbose, and verbose().

Referenced by main().

566  {
567  _verbose = verbose;
568  }
bool verbose() const
verbose information during optimization
OptimizationAlgorithm* g2o::SparseOptimizer::solver ( )
inline
void g2o::SparseOptimizer::sortVectorContainers ( )
protected

Definition at line 491 of file sparse_optimizer.cpp.

References _activeEdges, and _activeVertices.

Referenced by initializeOptimization().

492  {
493  // sort vector structures to get deterministic ordering based on IDs
494  sort(_activeVertices.begin(), _activeVertices.end(), VertexIDCompare());
495  sort(_activeEdges.begin(), _activeEdges.end(), EdgeIDCompare());
496  }
VertexContainer _activeVertices
sorted according to VertexIDCompare
EdgeContainer _activeEdges
sorted according to EdgeIDCompare
bool g2o::SparseOptimizer::terminate ( )
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().

189 {return _forceStopFlag ? (*_forceStopFlag) : false; }
bool g2o::SparseOptimizer::updateInitialization ( HyperGraph::VertexSet vset,
HyperGraph::EdgeSet eset 
)
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().

456  {
457  std::vector<HyperGraph::Vertex*> newVertices;
458  newVertices.reserve(vset.size());
459  _activeVertices.reserve(_activeVertices.size() + vset.size());
460  _activeEdges.reserve(_activeEdges.size() + eset.size());
461  for (HyperGraph::EdgeSet::iterator it = eset.begin(); it != eset.end(); ++it) {
462  OptimizableGraph::Edge* e = static_cast<OptimizableGraph::Edge*>(*it);
463  if (!e->allVerticesFixed()) _activeEdges.push_back(e);
464  }
465 
466  // update the index mapping
467  size_t next = _ivMap.size();
468  for (HyperGraph::VertexSet::iterator it = vset.begin(); it != vset.end(); ++it) {
470  if (! v->fixed()){
471  if (! v->marginalized()){
472  v->setHessianIndex(next);
473  _ivMap.push_back(v);
474  newVertices.push_back(v);
475  _activeVertices.push_back(v);
476  next++;
477  }
478  else // not supported right now
479  abort();
480  }
481  else {
482  v->setHessianIndex(-1);
483  }
484  }
485 
486  //if (newVertices.size() != vset.size())
487  //cerr << __PRETTY_FUNCTION__ << ": something went wrong " << PVAR(vset.size()) << " " << PVAR(newVertices.size()) << endl;
488  return _algorithm->updateStructure(newVertices, eset);
489  }
VertexContainer _ivMap
VertexContainer _activeVertices
sorted according to VertexIDCompare
virtual bool updateStructure(const std::vector< HyperGraph::Vertex * > &vset, const HyperGraph::EdgeSet &edges)=0
class G2O_CORE_API Vertex
class G2O_CORE_API Edge
EdgeContainer _activeEdges
sorted according to EdgeIDCompare
OptimizationAlgorithm * _algorithm
bool g2o::SparseOptimizer::verbose ( ) const
inline

verbose information during optimization

Definition at line 179 of file sparse_optimizer.h.

Referenced by computeInitialGuess(), main(), g2o::SparseOptimizerOnline::optimize(), optimize(), and setVerbose().

179 {return _verbose;}

Friends And Related Function Documentation

friend class ActivePathCostFunction
friend

Definition at line 54 of file sparse_optimizer.h.

Member Data Documentation

EdgeContainer g2o::SparseOptimizer::_activeEdges
protected
VertexContainer g2o::SparseOptimizer::_activeVertices
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().

OptimizationAlgorithm* g2o::SparseOptimizer::_algorithm
protected
BatchStatisticsContainer g2o::SparseOptimizer::_batchStatistics
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().

bool g2o::SparseOptimizer::_computeBatchStatistics
protected

Definition at line 309 of file sparse_optimizer.h.

Referenced by optimize(), and setComputeBatchStatistics().

bool* g2o::SparseOptimizer::_forceStopFlag
protected

Definition at line 291 of file sparse_optimizer.h.

Referenced by setForceStopFlag().

VertexContainer g2o::SparseOptimizer::_ivMap
protected
bool g2o::SparseOptimizer::_verbose
protected

Definition at line 292 of file sparse_optimizer.h.

Referenced by setVerbose().


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