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

#include <ConcurrentIncrementalFilter.h>

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

Classes

struct  Result
 

Public Types

typedef ConcurrentFilter Base
 typedef for base class More...
 
typedef boost::shared_ptr< ConcurrentIncrementalFiltershared_ptr
 
- Public Types inherited from gtsam::ConcurrentFilter
typedef boost::shared_ptr< ConcurrentFiltershared_ptr
 

Public Member Functions

Values calculateEstimate () const
 
template<class VALUE >
VALUE calculateEstimate (Key key) const
 
 ConcurrentIncrementalFilter (const ISAM2Params &parameters=ISAM2Params())
 
bool equals (const ConcurrentFilter &rhs, double tol=1e-9) const override
 
const VectorValuesgetDelta () const
 
const NonlinearFactorGraphgetFactors () const
 
const ISAM2getISAM2 () const
 
const ValuesgetLinearizationPoint () const
 
void getSmootherFactors (NonlinearFactorGraph &smootherFactors, Values &smootherValues) override
 
void getSummarizedFactors (NonlinearFactorGraph &filterSummarization, Values &filterSummarizationValues) override
 
void postsync () override
 
void presync () override
 
void print (const std::string &s="Concurrent Incremental Filter:\n", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
void synchronize (const NonlinearFactorGraph &smootherSummarization, const Values &smootherSummarizationValues) override
 
Result update (const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const boost::optional< FastList< Key > > &keysToMove=boost::none, const boost::optional< FactorIndices > &removeFactorIndices=boost::none)
 
 ~ConcurrentIncrementalFilter () override
 
- Public Member Functions inherited from gtsam::ConcurrentFilter
 ConcurrentFilter ()
 
virtual ~ConcurrentFilter ()
 

Protected Attributes

FactorIndices currentSmootherSummarizationSlots_
 The slots in factor graph that correspond to the current smoother summarization on the current separator. More...
 
ISAM2 isam2_
 The iSAM2 inference engine. More...
 
NonlinearFactorGraph previousSmootherSummarization_
 The smoother summarization on the old separator sent by the smoother during the last synchronization. More...
 
NonlinearFactorGraph smootherFactors_
 A temporary holding place for the set of full nonlinear factors being sent to the smoother. More...
 
NonlinearFactorGraph smootherShortcut_
 A set of conditional factors from the old separator to the current separator (recursively calculated during each filter update) More...
 
Values smootherValues_
 A temporary holding place for the linearization points of all keys being sent to the smoother. More...
 

Private Member Functions

NonlinearFactorGraph calculateFilterSummarization () const
 
void updateShortcut (const NonlinearFactorGraph &removedFactors)
 

Static Private Member Functions

static FactorIndices FindAdjacentFactors (const ISAM2 &isam2, const FastList< Key > &keys, const FactorIndices &factorsToIgnore)
 
static void RecursiveMarkAffectedKeys (const Key &key, const ISAM2Clique::shared_ptr &clique, std::set< Key > &additionalKeys)
 

Detailed Description

An iSAM2-based Batch Filter that implements the Concurrent Filtering and Smoother interface.

Definition at line 30 of file ConcurrentIncrementalFilter.h.

Member Typedef Documentation

typedef for base class

Definition at line 35 of file ConcurrentIncrementalFilter.h.

Definition at line 34 of file ConcurrentIncrementalFilter.h.

Constructor & Destructor Documentation

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

Default constructor

Definition at line 64 of file ConcurrentIncrementalFilter.h.

gtsam::ConcurrentIncrementalFilter::~ConcurrentIncrementalFilter ( )
inlineoverride

Default destructor

Definition at line 67 of file ConcurrentIncrementalFilter.h.

Member Function Documentation

Values gtsam::ConcurrentIncrementalFilter::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 98 of file ConcurrentIncrementalFilter.h.

template<class VALUE >
VALUE gtsam::ConcurrentIncrementalFilter::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 108 of file ConcurrentIncrementalFilter.h.

NonlinearFactorGraph gtsam::ConcurrentIncrementalFilter::calculateFilterSummarization ( ) const
private

Calculate marginal factors on the current separator variables using just the information in the filter

Definition at line 340 of file ConcurrentIncrementalFilter.cpp.

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

Check if two Concurrent Filters are equal

Implements gtsam::ConcurrentFilter.

Definition at line 32 of file ConcurrentIncrementalFilter.cpp.

FactorIndices gtsam::ConcurrentIncrementalFilter::FindAdjacentFactors ( const ISAM2 isam2,
const FastList< Key > &  keys,
const FactorIndices factorsToIgnore 
)
staticprivate

Find the set of iSAM2 factors adjacent to 'keys'

Definition at line 288 of file ConcurrentIncrementalFilter.cpp.

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

Access the current set of deltas to the linearization point

Definition at line 91 of file ConcurrentIncrementalFilter.h.

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

Access the current set of factors

Definition at line 76 of file ConcurrentIncrementalFilter.h.

const ISAM2& gtsam::ConcurrentIncrementalFilter::getISAM2 ( ) const
inline

Access the current linearization point

Definition at line 81 of file ConcurrentIncrementalFilter.h.

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

Access the current linearization point

Definition at line 86 of file ConcurrentIncrementalFilter.h.

void gtsam::ConcurrentIncrementalFilter::getSmootherFactors ( NonlinearFactorGraph smootherFactors,
Values smootherValues 
)
overridevirtual

Populate the provided containers with factors being sent to the smoother from the filter. These may be original nonlinear factors, or factors encoding a summarization of the filter information. The specifics will be implementation-specific for a given filter.

Parameters
smootherFactorsThe new factors to be added to the smoother
smootherValuesThe linearization points of any new variables

Implements gtsam::ConcurrentFilter.

Definition at line 243 of file ConcurrentIncrementalFilter.cpp.

void gtsam::ConcurrentIncrementalFilter::getSummarizedFactors ( NonlinearFactorGraph filterSummarization,
Values filterSummarizationValues 
)
overridevirtual

Populate the provided containers with factors that constitute the filter branch summarization needed by the smoother. Also, linearization points for the new root clique must be provided.

Parameters
summarizedFactorsThe summarized factors for the filter branch
rootValuesThe linearization points of the root clique variables

Implements gtsam::ConcurrentFilter.

Definition at line 227 of file ConcurrentIncrementalFilter.cpp.

void gtsam::ConcurrentIncrementalFilter::postsync ( )
overridevirtual

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

Reimplemented from gtsam::ConcurrentFilter.

Definition at line 255 of file ConcurrentIncrementalFilter.cpp.

void gtsam::ConcurrentIncrementalFilter::presync ( )
overridevirtual

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

Reimplemented from gtsam::ConcurrentFilter.

Definition at line 167 of file ConcurrentIncrementalFilter.cpp.

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

Implement a GTSAM standard 'print' function

Implements gtsam::ConcurrentFilter.

Definition at line 26 of file ConcurrentIncrementalFilter.cpp.

void gtsam::ConcurrentIncrementalFilter::RecursiveMarkAffectedKeys ( const Key key,
const ISAM2Clique::shared_ptr clique,
std::set< Key > &  additionalKeys 
)
staticprivate

Traverse the iSAM2 Bayes Tree, inserting all descendants of the provided index/key into 'additionalKeys'

Definition at line 268 of file ConcurrentIncrementalFilter.cpp.

void gtsam::ConcurrentIncrementalFilter::synchronize ( const NonlinearFactorGraph smootherSummarization,
const Values smootherSummarizationValues 
)
overridevirtual

Apply the updated version of the smoother branch summarized factors.

Parameters
summarizedFactorsAn updated version of the smoother branch summarized factors

Implements gtsam::ConcurrentFilter.

Definition at line 175 of file ConcurrentIncrementalFilter.cpp.

ConcurrentIncrementalFilter::Result gtsam::ConcurrentIncrementalFilter::update ( const NonlinearFactorGraph newFactors = NonlinearFactorGraph(),
const Values newTheta = Values(),
const boost::optional< FastList< Key > > &  keysToMove = boost::none,
const boost::optional< FactorIndices > &  removeFactorIndices = boost::none 
)

Add new factors and variables to the filter.

Add new measurements, and optionally new variables, to the filter. This runs a full update step of the derived filter algorithm

Parameters
newFactorsThe new factors to be added to the smoother
newThetaInitialization points for new variables to be added to the filter You must include here all new variables occurring in newFactors that were not already in the filter.
keysToMoveAn optional set of keys to move from the filter to the smoother
removeFactorIndicesAn optional set of indices corresponding to the factors you want to remove from the graph

Definition at line 45 of file ConcurrentIncrementalFilter.cpp.

void gtsam::ConcurrentIncrementalFilter::updateShortcut ( const NonlinearFactorGraph removedFactors)
private

Update the shortcut marginal between the current separator keys and the previous separator keys

  • ************************************************************************* */

Definition at line 312 of file ConcurrentIncrementalFilter.cpp.

Member Data Documentation

FactorIndices gtsam::ConcurrentIncrementalFilter::currentSmootherSummarizationSlots_
protected

The slots in factor graph that correspond to the current smoother summarization on the current separator.

Definition at line 173 of file ConcurrentIncrementalFilter.h.

ISAM2 gtsam::ConcurrentIncrementalFilter::isam2_
protected

The iSAM2 inference engine.

Definition at line 169 of file ConcurrentIncrementalFilter.h.

NonlinearFactorGraph gtsam::ConcurrentIncrementalFilter::previousSmootherSummarization_
protected

The smoother summarization on the old separator sent by the smoother during the last synchronization.

Definition at line 172 of file ConcurrentIncrementalFilter.h.

NonlinearFactorGraph gtsam::ConcurrentIncrementalFilter::smootherFactors_
protected

A temporary holding place for the set of full nonlinear factors being sent to the smoother.

Definition at line 177 of file ConcurrentIncrementalFilter.h.

NonlinearFactorGraph gtsam::ConcurrentIncrementalFilter::smootherShortcut_
protected

A set of conditional factors from the old separator to the current separator (recursively calculated during each filter update)

Definition at line 174 of file ConcurrentIncrementalFilter.h.

Values gtsam::ConcurrentIncrementalFilter::smootherValues_
protected

A temporary holding place for the linearization points of all keys being sent to the smoother.

Definition at line 178 of file ConcurrentIncrementalFilter.h.


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


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