Classes | Public Types | Public Member Functions | Protected Attributes | Private Member Functions | List of all members
gtsam::ConcurrentIncrementalSmoother Class Reference

#include <ConcurrentIncrementalSmoother.h>

Inheritance diagram for gtsam::ConcurrentIncrementalSmoother:
Inheritance graph
[legend]

Classes

struct  Result
 

Public Types

typedef ConcurrentSmoother Base
 typedef for base class More...
 
typedef std::shared_ptr< ConcurrentIncrementalSmoothershared_ptr
 
- Public Types inherited from gtsam::ConcurrentSmoother
typedef std::shared_ptr< ConcurrentSmoothershared_ptr
 

Public Member Functions

Values calculateEstimate () const
 
template<class VALUE >
VALUE calculateEstimate (Key key) const
 
 ConcurrentIncrementalSmoother (const ISAM2Params &parameters=ISAM2Params())
 
bool equals (const ConcurrentSmoother &rhs, double tol=1e-9) const override
 
const VectorValuesgetDelta () const
 
const NonlinearFactorGraphgetFactors () const
 
const ValuesgetLinearizationPoint () const
 
void getSummarizedFactors (NonlinearFactorGraph &summarizedFactors, Values &separatorValues) override
 
void postsync () override
 
void presync () override
 
void print (const std::string &s="Concurrent Incremental Smoother:\, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
void synchronize (const NonlinearFactorGraph &smootherFactors, const Values &smootherValues, const NonlinearFactorGraph &summarizedFactors, const Values &separatorValues) override
 
Result update (const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const std::optional< FactorIndices > &removeFactorIndices={})
 
 ~ConcurrentIncrementalSmoother () override
 
- Public Member Functions inherited from gtsam::ConcurrentSmoother
 ConcurrentSmoother ()
 
virtual ~ConcurrentSmoother ()=default
 

Protected Attributes

NonlinearFactorGraph filterSummarizationFactors_
 New filter summarization factors to replace the existing filter summarization during the next update. More...
 
FactorIndices filterSummarizationSlots_
 The slots in factor graph that correspond to the current filter summarization factors. More...
 
ISAM2 isam2_
 iSAM2 inference engine More...
 
Values separatorValues_
 The linearization points of the separator variables. These should not be changed during optimization. More...
 
NonlinearFactorGraph smootherFactors_
 New factors to be added to the smoother during the next update. More...
 
NonlinearFactorGraph smootherSummarization_
 A temporary holding place for calculated smoother summarization. More...
 
Values smootherValues_
 New variables to be added to the smoother during the next update. More...
 
bool synchronizationUpdatesAvailable_
 Flag indicating the currently stored synchronization updates have not been applied yet. More...
 

Private Member Functions

void updateSmootherSummarization ()
 

Detailed Description

A Levenberg-Marquardt Batch Smoother that implements the Concurrent Filtering and Smoother interface.

Definition at line 30 of file ConcurrentIncrementalSmoother.h.

Member Typedef Documentation

◆ Base

typedef for base class

Definition at line 34 of file ConcurrentIncrementalSmoother.h.

◆ shared_ptr

Definition at line 33 of file ConcurrentIncrementalSmoother.h.

Constructor & Destructor Documentation

◆ ConcurrentIncrementalSmoother()

gtsam::ConcurrentIncrementalSmoother::ConcurrentIncrementalSmoother ( const ISAM2Params parameters = ISAM2Params())
inline

Default constructor

Definition at line 54 of file ConcurrentIncrementalSmoother.h.

◆ ~ConcurrentIncrementalSmoother()

gtsam::ConcurrentIncrementalSmoother::~ConcurrentIncrementalSmoother ( )
inlineoverride

Default destructor

Definition at line 57 of file ConcurrentIncrementalSmoother.h.

Member Function Documentation

◆ calculateEstimate() [1/2]

Values gtsam::ConcurrentIncrementalSmoother::calculateEstimate ( ) const
inline

Compute the current best estimate of all variables and return a full Values structure. If only a single variable is needed, it may be faster to call calculateEstimate(const KEY&).

Definition at line 83 of file ConcurrentIncrementalSmoother.h.

◆ calculateEstimate() [2/2]

template<class VALUE >
VALUE gtsam::ConcurrentIncrementalSmoother::calculateEstimate ( Key  key) const
inline

Compute the current best estimate of a single variable. This is generally faster than calling the no-argument version of calculateEstimate if only specific variables are needed.

Parameters
key
Returns

Definition at line 93 of file ConcurrentIncrementalSmoother.h.

◆ equals()

bool gtsam::ConcurrentIncrementalSmoother::equals ( const ConcurrentSmoother rhs,
double  tol = 1e-9 
) const
overridevirtual

Check if two Concurrent Smoothers are equal

Implements gtsam::ConcurrentSmoother.

Definition at line 33 of file ConcurrentIncrementalSmoother.cpp.

◆ getDelta()

const VectorValues& gtsam::ConcurrentIncrementalSmoother::getDelta ( ) const
inline

Access the current set of deltas to the linearization point

Definition at line 76 of file ConcurrentIncrementalSmoother.h.

◆ getFactors()

const NonlinearFactorGraph& gtsam::ConcurrentIncrementalSmoother::getFactors ( ) const
inline

Access the current set of factors

Definition at line 66 of file ConcurrentIncrementalSmoother.h.

◆ getLinearizationPoint()

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

Access the current linearization point

Definition at line 71 of file ConcurrentIncrementalSmoother.h.

◆ getSummarizedFactors()

void gtsam::ConcurrentIncrementalSmoother::getSummarizedFactors ( NonlinearFactorGraph summarizedFactors,
Values separatorValues 
)
overridevirtual

Populate the provided containers with factors that constitute the smoother branch summarization needed by the filter.

Parameters
summarizedFactorsThe summarized factors for the filter branch

Implements gtsam::ConcurrentSmoother.

Definition at line 140 of file ConcurrentIncrementalSmoother.cpp.

◆ postsync()

void gtsam::ConcurrentIncrementalSmoother::postsync ( )
overridevirtual

Perform any required operations after the synchronization process finishes. Called by 'synchronize'

Reimplemented from gtsam::ConcurrentSmoother.

Definition at line 174 of file ConcurrentIncrementalSmoother.cpp.

◆ presync()

void gtsam::ConcurrentIncrementalSmoother::presync ( )
overridevirtual

Perform any required operations before the synchronization process starts. Called by 'synchronize'

Reimplemented from gtsam::ConcurrentSmoother.

Definition at line 132 of file ConcurrentIncrementalSmoother.cpp.

◆ print()

void gtsam::ConcurrentIncrementalSmoother::print ( const std::string &  s = "Concurrent Incremental Smoother:\n",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const
overridevirtual

Implement a GTSAM standard 'print' function

Implements gtsam::ConcurrentSmoother.

Definition at line 27 of file ConcurrentIncrementalSmoother.cpp.

◆ synchronize()

void gtsam::ConcurrentIncrementalSmoother::synchronize ( const NonlinearFactorGraph smootherFactors,
const Values smootherValues,
const NonlinearFactorGraph summarizedFactors,
const Values separatorValues 
)
overridevirtual

Apply the new smoother factors sent by the filter, and the updated version of the filter branch summarized factors.

Parameters
smootherFactorsA set of new factors added to the smoother from the filter
smootherValuesLinearization points for any new variables
summarizedFactorsAn updated version of the filter branch summarized factors
rootValuesThe linearization point of the root variables

Implements gtsam::ConcurrentSmoother.

Definition at line 154 of file ConcurrentIncrementalSmoother.cpp.

◆ update()

ConcurrentIncrementalSmoother::Result gtsam::ConcurrentIncrementalSmoother::update ( const NonlinearFactorGraph newFactors = NonlinearFactorGraph(),
const Values newTheta = Values(),
const std::optional< FactorIndices > &  removeFactorIndices = {} 
)

Add new factors and variables to the smoother.

Add new measurements, and optionally new variables, to the smoother. This runs a full step of the ISAM2 algorithm, relinearizing and updating the solution as needed, according to the wildfire and relinearize thresholds.

Parameters
newFactorsThe new factors to be added to the smoother
newThetaInitialization points for new variables to be added to the smoother You must include here all new variables occuring in newFactors (which were not already in the smoother). There must not be any variables here that do not occur in newFactors, and additionally, variables that were already in the system must not be included here.

Definition at line 47 of file ConcurrentIncrementalSmoother.cpp.

◆ updateSmootherSummarization()

void gtsam::ConcurrentIncrementalSmoother::updateSmootherSummarization ( )
private

Calculate the smoother marginal factors on the separator variables

Definition at line 182 of file ConcurrentIncrementalSmoother.cpp.

Member Data Documentation

◆ filterSummarizationFactors_

NonlinearFactorGraph gtsam::ConcurrentIncrementalSmoother::filterSummarizationFactors_
protected

New filter summarization factors to replace the existing filter summarization during the next update.

Definition at line 153 of file ConcurrentIncrementalSmoother.h.

◆ filterSummarizationSlots_

FactorIndices gtsam::ConcurrentIncrementalSmoother::filterSummarizationSlots_
protected

The slots in factor graph that correspond to the current filter summarization factors.

Definition at line 155 of file ConcurrentIncrementalSmoother.h.

◆ isam2_

ISAM2 gtsam::ConcurrentIncrementalSmoother::isam2_
protected

iSAM2 inference engine

Definition at line 148 of file ConcurrentIncrementalSmoother.h.

◆ separatorValues_

Values gtsam::ConcurrentIncrementalSmoother::separatorValues_
protected

The linearization points of the separator variables. These should not be changed during optimization.

Definition at line 154 of file ConcurrentIncrementalSmoother.h.

◆ smootherFactors_

NonlinearFactorGraph gtsam::ConcurrentIncrementalSmoother::smootherFactors_
protected

New factors to be added to the smoother during the next update.

Definition at line 151 of file ConcurrentIncrementalSmoother.h.

◆ smootherSummarization_

NonlinearFactorGraph gtsam::ConcurrentIncrementalSmoother::smootherSummarization_
protected

A temporary holding place for calculated smoother summarization.

Definition at line 159 of file ConcurrentIncrementalSmoother.h.

◆ smootherValues_

Values gtsam::ConcurrentIncrementalSmoother::smootherValues_
protected

New variables to be added to the smoother during the next update.

Definition at line 152 of file ConcurrentIncrementalSmoother.h.

◆ synchronizationUpdatesAvailable_

bool gtsam::ConcurrentIncrementalSmoother::synchronizationUpdatesAvailable_
protected

Flag indicating the currently stored synchronization updates have not been applied yet.

Definition at line 156 of file ConcurrentIncrementalSmoother.h.


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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:46:16