Public Member Functions | Static Public Member Functions | Public Attributes | Static Protected Attributes | List of all members
g2o::G2OBatchStatistics Struct Reference

statistics about the optimization More...

#include <batch_stats.h>

Public Member Functions

 G2OBatchStatistics ()
 

Static Public Member Functions

static G2OBatchStatisticsglobalStats ()
 
static void setGlobalStats (G2OBatchStatistics *b)
 

Public Attributes

double chi2
 total chi2 More...
 
size_t choleskyNNZ
 number of non-zeros in the cholesky factor More...
 
size_t hessianDimension
 rows / cols of the Hessian More...
 
size_t hessianLandmarkDimension
 dimension of the landmark matrix in Schur More...
 
size_t hessianPoseDimension
 dimension of the pose matrix in Schur More...
 
int iteration
 which iteration More...
 
int iterationsLinearSolver
 iterations of PCG, (0 if not used, i.e., Cholesky) More...
 
int levenbergIterations
 number of iterations performed by LM More...
 
int numEdges
 how many edges More...
 
int numVertices
 how many vertices are involved More...
 
double timeIteration
 total time; More...
 
double timeLinearize
 jacobians More...
 
double timeLinearSolution
 total time for solving Ax=b (including detup for schur) More...
 
double timeLinearSolver
 time for solving, excluding Schur setup More...
 
double timeMarginals
 computing the inverse elements (solve blocks) and thus the marginal covariances More...
 
double timeNumericDecomposition
 numeric decomposition (0 if not done) More...
 
double timeQuadraticForm
 construct the quadratic form in the graph More...
 
double timeResiduals
 residuals More...
 
double timeSchurComplement
 compute schur complement (0 if not done) More...
 
double timeSymbolicDecomposition
 symbolic decomposition (0 if not done) More...
 
double timeUpdate
 time to apply the update More...
 

Static Protected Attributes

static G2OBatchStatistics_globalStats =0
 

Detailed Description

statistics about the optimization

Definition at line 39 of file batch_stats.h.

Constructor & Destructor Documentation

g2o::G2OBatchStatistics::G2OBatchStatistics ( )

Definition at line 40 of file batch_stats.cpp.

Member Function Documentation

static G2OBatchStatistics* g2o::G2OBatchStatistics::globalStats ( )
inlinestatic

Definition at line 72 of file batch_stats.h.

void g2o::G2OBatchStatistics::setGlobalStats ( G2OBatchStatistics b)
static

Definition at line 85 of file batch_stats.cpp.

Member Data Documentation

G2OBatchStatistics * g2o::G2OBatchStatistics::_globalStats =0
staticprotected

Definition at line 75 of file batch_stats.h.

double g2o::G2OBatchStatistics::chi2

total chi2

Definition at line 44 of file batch_stats.h.

size_t g2o::G2OBatchStatistics::choleskyNNZ

number of non-zeros in the cholesky factor

Definition at line 70 of file batch_stats.h.

size_t g2o::G2OBatchStatistics::hessianDimension

rows / cols of the Hessian

Definition at line 67 of file batch_stats.h.

size_t g2o::G2OBatchStatistics::hessianLandmarkDimension

dimension of the landmark matrix in Schur

Definition at line 69 of file batch_stats.h.

size_t g2o::G2OBatchStatistics::hessianPoseDimension

dimension of the pose matrix in Schur

Definition at line 68 of file batch_stats.h.

int g2o::G2OBatchStatistics::iteration

which iteration

Definition at line 41 of file batch_stats.h.

int g2o::G2OBatchStatistics::iterationsLinearSolver

iterations of PCG, (0 if not used, i.e., Cholesky)

Definition at line 60 of file batch_stats.h.

int g2o::G2OBatchStatistics::levenbergIterations

number of iterations performed by LM

Definition at line 51 of file batch_stats.h.

int g2o::G2OBatchStatistics::numEdges

how many edges

Definition at line 43 of file batch_stats.h.

int g2o::G2OBatchStatistics::numVertices

how many vertices are involved

Definition at line 42 of file batch_stats.h.

double g2o::G2OBatchStatistics::timeIteration

total time;

Definition at line 62 of file batch_stats.h.

double g2o::G2OBatchStatistics::timeLinearize

jacobians

Definition at line 49 of file batch_stats.h.

double g2o::G2OBatchStatistics::timeLinearSolution

total time for solving Ax=b (including detup for schur)

Definition at line 58 of file batch_stats.h.

double g2o::G2OBatchStatistics::timeLinearSolver

time for solving, excluding Schur setup

Definition at line 59 of file batch_stats.h.

double g2o::G2OBatchStatistics::timeMarginals

computing the inverse elements (solve blocks) and thus the marginal covariances

Definition at line 64 of file batch_stats.h.

double g2o::G2OBatchStatistics::timeNumericDecomposition

numeric decomposition (0 if not done)

Definition at line 57 of file batch_stats.h.

double g2o::G2OBatchStatistics::timeQuadraticForm

construct the quadratic form in the graph

Definition at line 50 of file batch_stats.h.

double g2o::G2OBatchStatistics::timeResiduals

residuals

timings

Definition at line 48 of file batch_stats.h.

double g2o::G2OBatchStatistics::timeSchurComplement

compute schur complement (0 if not done)

Definition at line 53 of file batch_stats.h.

double g2o::G2OBatchStatistics::timeSymbolicDecomposition

symbolic decomposition (0 if not done)

Definition at line 56 of file batch_stats.h.

double g2o::G2OBatchStatistics::timeUpdate

time to apply the update

Definition at line 61 of file batch_stats.h.


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


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:06