Protected Attributes | List of all members
gtsam::NonlinearISAM Class Reference

#include <NonlinearISAM.h>

Public Member Functions

Standard Constructors
 NonlinearISAM (int reorderInterval=1, const GaussianFactorGraph::Eliminate &eliminationFunction=GaussianFactorGraph::EliminationTraitsType::DefaultEliminate)
 
Standard Interface
Values estimate () const
 
Matrix marginalCovariance (Key key) const
 
const GaussianISAMbayesTree () const
 
const ValuesgetLinearizationPoint () const
 
const NonlinearFactorGraphgetFactorsUnsafe () const
 
int reorderInterval () const
 TODO: comment. More...
 
int reorderCounter () const
 TODO: comment. More...
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
 
void printStats () const
 
void saveGraph (const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
 
Advanced Interface
void update (const NonlinearFactorGraph &newFactors, const Values &initialValues)
 
void reorder_relinearize ()
 

Protected Attributes

GaussianFactorGraph::Eliminate eliminationFunction_
 
NonlinearFactorGraph factors_
 
gtsam::GaussianISAM isam_
 
Values linPoint_
 
int reorderCounter_
 
int reorderInterval_
 

Detailed Description

Wrapper class to manage ISAM in a nonlinear context

Definition at line 27 of file NonlinearISAM.h.

Constructor & Destructor Documentation

◆ NonlinearISAM()

gtsam::NonlinearISAM::NonlinearISAM ( int  reorderInterval = 1,
const GaussianFactorGraph::Eliminate eliminationFunction = GaussianFactorGraph::EliminationTraitsType::DefaultEliminate 
)
inline

Periodically reorder and relinearize

Parameters
reorderIntervalis the number of updates between reorderings, 0 never reorders (and is dangerous for memory consumption) 1 (default) reorders every time, in worse case is batch every update typical values are 50 or 100

Definition at line 58 of file NonlinearISAM.h.

Member Function Documentation

◆ bayesTree()

const GaussianISAM& gtsam::NonlinearISAM::bayesTree ( ) const
inline

access the underlying bayes tree

Definition at line 75 of file NonlinearISAM.h.

◆ estimate()

Values gtsam::NonlinearISAM::estimate ( ) const

Return the current solution estimate

Definition at line 80 of file NonlinearISAM.cpp.

◆ getFactorsUnsafe()

const NonlinearFactorGraph& gtsam::NonlinearISAM::getFactorsUnsafe ( ) const
inline

get underlying nonlinear graph

Definition at line 81 of file NonlinearISAM.h.

◆ getLinearizationPoint()

const Values& gtsam::NonlinearISAM::getLinearizationPoint ( ) const
inline

Return the current linearization point

Definition at line 78 of file NonlinearISAM.h.

◆ marginalCovariance()

Matrix gtsam::NonlinearISAM::marginalCovariance ( Key  key) const

find the marginal covariance for a single variable

Definition at line 88 of file NonlinearISAM.cpp.

◆ print()

void gtsam::NonlinearISAM::print ( const std::string &  s = "",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const

prints out all contents of the system

Definition at line 93 of file NonlinearISAM.cpp.

◆ printStats()

void gtsam::NonlinearISAM::printStats ( ) const

prints out clique statistics

Definition at line 101 of file NonlinearISAM.cpp.

◆ reorder_relinearize()

void gtsam::NonlinearISAM::reorder_relinearize ( )

Relinearization and reordering of variables

Definition at line 59 of file NonlinearISAM.cpp.

◆ reorderCounter()

int gtsam::NonlinearISAM::reorderCounter ( ) const
inline

TODO: comment.

Definition at line 85 of file NonlinearISAM.h.

◆ reorderInterval()

int gtsam::NonlinearISAM::reorderInterval ( ) const
inline

TODO: comment.

get counters

Definition at line 84 of file NonlinearISAM.h.

◆ saveGraph()

void gtsam::NonlinearISAM::saveGraph ( const std::string &  s,
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const

saves the Tree to a text file in GraphViz format

Definition at line 30 of file NonlinearISAM.cpp.

◆ update()

void gtsam::NonlinearISAM::update ( const NonlinearFactorGraph newFactors,
const Values initialValues 
)

Add new factors along with their initial linearization points

Definition at line 35 of file NonlinearISAM.cpp.

Member Data Documentation

◆ eliminationFunction_

GaussianFactorGraph::Eliminate gtsam::NonlinearISAM::eliminationFunction_
protected

The elimination function

Definition at line 44 of file NonlinearISAM.h.

◆ factors_

NonlinearFactorGraph gtsam::NonlinearISAM::factors_
protected

The original factors, used when relinearizing

Definition at line 37 of file NonlinearISAM.h.

◆ isam_

gtsam::GaussianISAM gtsam::NonlinearISAM::isam_
protected

The internal iSAM object

Definition at line 31 of file NonlinearISAM.h.

◆ linPoint_

Values gtsam::NonlinearISAM::linPoint_
protected

The current linearization point

Definition at line 34 of file NonlinearISAM.h.

◆ reorderCounter_

int gtsam::NonlinearISAM::reorderCounter_
protected

Definition at line 41 of file NonlinearISAM.h.

◆ reorderInterval_

int gtsam::NonlinearISAM::reorderInterval_
protected

The reordering interval and counter

Definition at line 40 of file NonlinearISAM.h.


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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:47:05