Public Types | Public Member Functions | Public Attributes | List of all members
gtsam::ISAM2Params Struct Reference

#include <ISAM2Params.h>

Public Types

enum  Factorization { CHOLESKY, QR }
 
typedef boost::variant< ISAM2GaussNewtonParams, ISAM2DoglegParamsOptimizationParams
 
typedef boost::variant< double, FastMap< char, Vector > > RelinearizationThreshold
 

Public Member Functions

 ISAM2Params (OptimizationParams _optimizationParams=ISAM2GaussNewtonParams(), RelinearizationThreshold _relinearizeThreshold=0.1, int _relinearizeSkip=10, bool _enableRelinearization=true, bool _evaluateNonlinearError=false, Factorization _factorization=ISAM2Params::CHOLESKY, bool _cacheLinearizedFactors=true, const KeyFormatter &_keyFormatter=DefaultKeyFormatter, bool _enableDetailedResults=false)
 
void print (const std::string &str="") const
 print iSAM2 parameters More...
 
Getters and Setters for all properties
OptimizationParams getOptimizationParams () const
 
RelinearizationThreshold getRelinearizeThreshold () const
 
int getRelinearizeSkip () const
 
bool isEnableRelinearization () const
 
bool isEvaluateNonlinearError () const
 
std::string getFactorization () const
 
bool isCacheLinearizedFactors () const
 
KeyFormatter getKeyFormatter () const
 
bool isEnableDetailedResults () const
 
bool isEnablePartialRelinearizationCheck () const
 
void setOptimizationParams (OptimizationParams optimizationParams)
 
void setRelinearizeThreshold (RelinearizationThreshold relinearizeThreshold)
 
void setRelinearizeSkip (int relinearizeSkip)
 
void setEnableRelinearization (bool enableRelinearization)
 
void setEvaluateNonlinearError (bool evaluateNonlinearError)
 
void setFactorization (const std::string &factorization)
 
void setCacheLinearizedFactors (bool cacheLinearizedFactors)
 
void setKeyFormatter (KeyFormatter keyFormatter)
 
void setEnableDetailedResults (bool enableDetailedResults)
 
void setEnablePartialRelinearizationCheck (bool enablePartialRelinearizationCheck)
 
GaussianFactorGraph::Eliminate getEliminationFunction () const
 

Static Public Member Functions

Some utilities
static Factorization factorizationTranslator (const std::string &str)
 
static std::string factorizationTranslator (const Factorization &value)
 

Public Attributes

bool cacheLinearizedFactors
 
bool enableDetailedResults
 
bool enablePartialRelinearizationCheck
 
bool enableRelinearization
 
bool evaluateNonlinearError
 
Factorization factorization
 
bool findUnusedFactorSlots
 
KeyFormatter keyFormatter
 
OptimizationParams optimizationParams
 
int relinearizeSkip
 
RelinearizationThreshold relinearizeThreshold
 

Detailed Description

Definition at line 135 of file ISAM2Params.h.

Member Typedef Documentation

Either ISAM2GaussNewtonParams or ISAM2DoglegParams

Definition at line 137 of file ISAM2Params.h.

typedef boost::variant<double, FastMap<char, Vector> > gtsam::ISAM2Params::RelinearizationThreshold

Either a constant relinearization threshold or a per-variable-type set of thresholds

Definition at line 140 of file ISAM2Params.h.

Member Enumeration Documentation

Enumerator
CHOLESKY 
QR 

Definition at line 181 of file ISAM2Params.h.

Constructor & Destructor Documentation

gtsam::ISAM2Params::ISAM2Params ( OptimizationParams  _optimizationParams = ISAM2GaussNewtonParams(),
RelinearizationThreshold  _relinearizeThreshold = 0.1,
int  _relinearizeSkip = 10,
bool  _enableRelinearization = true,
bool  _evaluateNonlinearError = false,
Factorization  _factorization = ISAM2Params::CHOLESKY,
bool  _cacheLinearizedFactors = true,
const KeyFormatter _keyFormatter = DefaultKeyFormatter,
bool  _enableDetailedResults = false 
)
inline

Specify parameters as constructor arguments See the documentation of member variables above.

Parameters
_keyFormattersee ISAM2::Params::keyFormatter,

Definition at line 230 of file ISAM2Params.h.

Member Function Documentation

ISAM2Params::Factorization gtsam::ISAM2Params::factorizationTranslator ( const std::string &  str)
static

Definition at line 60 of file ISAM2Params.cpp.

string gtsam::ISAM2Params::factorizationTranslator ( const Factorization value)
static

Definition at line 72 of file ISAM2Params.cpp.

GaussianFactorGraph::Eliminate gtsam::ISAM2Params::getEliminationFunction ( ) const
inline

Definition at line 348 of file ISAM2Params.h.

std::string gtsam::ISAM2Params::getFactorization ( ) const
inline

Definition at line 306 of file ISAM2Params.h.

KeyFormatter gtsam::ISAM2Params::getKeyFormatter ( ) const
inline

Definition at line 310 of file ISAM2Params.h.

OptimizationParams gtsam::ISAM2Params::getOptimizationParams ( ) const
inline

Definition at line 297 of file ISAM2Params.h.

int gtsam::ISAM2Params::getRelinearizeSkip ( ) const
inline

Definition at line 303 of file ISAM2Params.h.

RelinearizationThreshold gtsam::ISAM2Params::getRelinearizeThreshold ( ) const
inline

Definition at line 300 of file ISAM2Params.h.

bool gtsam::ISAM2Params::isCacheLinearizedFactors ( ) const
inline

Definition at line 309 of file ISAM2Params.h.

bool gtsam::ISAM2Params::isEnableDetailedResults ( ) const
inline

Definition at line 311 of file ISAM2Params.h.

bool gtsam::ISAM2Params::isEnablePartialRelinearizationCheck ( ) const
inline

Definition at line 312 of file ISAM2Params.h.

bool gtsam::ISAM2Params::isEnableRelinearization ( ) const
inline

Definition at line 304 of file ISAM2Params.h.

bool gtsam::ISAM2Params::isEvaluateNonlinearError ( ) const
inline

Definition at line 305 of file ISAM2Params.h.

void gtsam::ISAM2Params::print ( const std::string &  str = "") const
inline

print iSAM2 parameters

Definition at line 252 of file ISAM2Params.h.

void gtsam::ISAM2Params::setCacheLinearizedFactors ( bool  cacheLinearizedFactors)
inline

Definition at line 334 of file ISAM2Params.h.

void gtsam::ISAM2Params::setEnableDetailedResults ( bool  enableDetailedResults)
inline

Definition at line 340 of file ISAM2Params.h.

void gtsam::ISAM2Params::setEnablePartialRelinearizationCheck ( bool  enablePartialRelinearizationCheck)
inline

Definition at line 343 of file ISAM2Params.h.

void gtsam::ISAM2Params::setEnableRelinearization ( bool  enableRelinearization)
inline

Definition at line 325 of file ISAM2Params.h.

void gtsam::ISAM2Params::setEvaluateNonlinearError ( bool  evaluateNonlinearError)
inline

Definition at line 328 of file ISAM2Params.h.

void gtsam::ISAM2Params::setFactorization ( const std::string &  factorization)
inline

Definition at line 331 of file ISAM2Params.h.

void gtsam::ISAM2Params::setKeyFormatter ( KeyFormatter  keyFormatter)
inline

Definition at line 337 of file ISAM2Params.h.

void gtsam::ISAM2Params::setOptimizationParams ( OptimizationParams  optimizationParams)
inline

Definition at line 316 of file ISAM2Params.h.

void gtsam::ISAM2Params::setRelinearizeSkip ( int  relinearizeSkip)
inline

Definition at line 322 of file ISAM2Params.h.

void gtsam::ISAM2Params::setRelinearizeThreshold ( RelinearizationThreshold  relinearizeThreshold)
inline

Definition at line 319 of file ISAM2Params.h.

Member Data Documentation

bool gtsam::ISAM2Params::cacheLinearizedFactors

Whether to cache linear factors (default: true). This can improve performance if linearization is expensive, but can hurt performance if linearization is very cleap due to computation to look up additional keys.

Definition at line 200 of file ISAM2Params.h.

bool gtsam::ISAM2Params::enableDetailedResults

Whether to compute and return ISAM2Result::detailedResults, this can increase running time (default: false)

Definition at line 206 of file ISAM2Params.h.

bool gtsam::ISAM2Params::enablePartialRelinearizationCheck

Check variables for relinearization in tree-order, stopping the check once a variable does not need to be relinearized (default: false). This can improve speed by only checking a small part of the top of the tree. However, variables below the check cut-off can accumulate significant deltas without triggering relinearization. This is particularly useful in exploration scenarios where real-time performance is desired over correctness. Use with caution.

Definition at line 218 of file ISAM2Params.h.

bool gtsam::ISAM2Params::enableRelinearization

Controls whether ISAM2 will ever relinearize any variables (default: true)

Definition at line 174 of file ISAM2Params.h.

bool gtsam::ISAM2Params::evaluateNonlinearError

Whether to evaluate the nonlinear error before and after the update, to return in ISAM2Result from update()

Definition at line 177 of file ISAM2Params.h.

Factorization gtsam::ISAM2Params::factorization

Specifies whether to use QR or CHOESKY numerical factorization (default: CHOLESKY). Cholesky is faster but potentially numerically unstable for poorly-conditioned problems, which can occur when uncertainty is very low in some variables (or dimensions of variables) and very high in others. QR is slower but more numerically stable in poorly-conditioned problems. We suggest using the default of Cholesky unless gtsam sometimes throws IndefiniteLinearSystemException when your problem's Hessian is actually positive definite. For positive definite problems, numerical error accumulation can cause the problem to become numerically negative or indefinite as solving proceeds, especially when using Cholesky.

Definition at line 193 of file ISAM2Params.h.

bool gtsam::ISAM2Params::findUnusedFactorSlots

When you will be removing many factors, e.g. when using ISAM2 as a fixed-lag smoother, enable this option to add factors in the first available factor slots, to avoid accumulating nullptr factor slots, at the cost of having to search for slots every time a factor is added.

Definition at line 224 of file ISAM2Params.h.

KeyFormatter gtsam::ISAM2Params::keyFormatter

A KeyFormatter for when keys are printed during debugging (default: DefaultKeyFormatter)

Definition at line 203 of file ISAM2Params.h.

OptimizationParams gtsam::ISAM2Params::optimizationParams

Optimization parameters, this both selects the nonlinear optimization method and specifies its parameters, either ISAM2GaussNewtonParams or ISAM2DoglegParams. In the former, Gauss-Newton optimization will be used with the specified parameters, and in the latter Powell's dog-leg algorithm will be used with the specified parameters.

Definition at line 150 of file ISAM2Params.h.

int gtsam::ISAM2Params::relinearizeSkip

Only relinearize any variables every relinearizeSkip calls to ISAM2::update (default: 10)

Definition at line 170 of file ISAM2Params.h.

RelinearizationThreshold gtsam::ISAM2Params::relinearizeThreshold

Only relinearize variables whose linear delta magnitude is greater than this threshold (default: 0.1). If this is a FastMap<char,Vector> instead of a double, then the threshold is specified for each dimension of each variable type. This parameter then maps from a character indicating the variable type to a Vector of thresholds for each dimension of that variable. For example, if Pose keys are of type TypedSymbol<'x',Pose3>, and landmark keys are of type TypedSymbol<'l',Point3>, then appropriate entries would be added with:

FastMap<char,Vector> thresholds;
thresholds['x'] = (Vector(6) << 0.1, 0.1, 0.1, 0.5, 0.5, 0.5).finished();
// 0.1 rad rotation threshold, 0.5 m translation threshold thresholds['l'] =
Vector3(1.0, 1.0, 1.0); // 1.0 m landmark position threshold
params.relinearizeThreshold = thresholds;

Definition at line 168 of file ISAM2Params.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:17