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

#include <ConcurrentBatchFilter.h>

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

Classes

struct  Result
 

Public Types

typedef ConcurrentFilter Base
 typedef for base class More...
 
typedef boost::shared_ptr< ConcurrentBatchFiltershared_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
 
 ConcurrentBatchFilter (const LevenbergMarquardtParams &parameters=LevenbergMarquardtParams())
 
bool equals (const ConcurrentFilter &rhs, double tol=1e-9) const override
 
const VectorValuesgetDelta () const
 
const NonlinearFactorGraphgetFactors () const
 
const ValuesgetLinearizationPoint () const
 
const OrderinggetOrdering () 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 Batch Filter:\n", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
void synchronize (const NonlinearFactorGraph &smootherSummarization, const Values &smootherSummarizationValues) override
 
virtual Result update (const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const boost::optional< FastList< Key > > &keysToMove=boost::none, const boost::optional< std::vector< size_t > > &removeFactorIndices=boost::none)
 
 ~ConcurrentBatchFilter () override
 
- Public Member Functions inherited from gtsam::ConcurrentFilter
 ConcurrentFilter ()
 
virtual ~ConcurrentFilter ()
 

Protected Attributes

std::queue< size_tavailableSlots_
 The set of available factor graph slots caused by deleting factors. More...
 
VectorValues delta_
 The current set of linear deltas from the linearization point. More...
 
NonlinearFactorGraph factors_
 The set of all factors currently in the filter. More...
 
NonlinearFactorGraph filterSummarization_
 A temporary holding place for calculated filter summarization factors to be sent to the smoother. More...
 
Ordering ordering_
 The current ordering used to calculate the linear deltas. More...
 
LevenbergMarquardtParams parameters_
 LM parameters. More...
 
std::vector< size_tseparatorSummarizationSlots_
 The slots in factor graph that correspond to the current smoother summarization on the current separator. More...
 
Values separatorValues_
 The linearization points of the separator variables. These should not be updated during optimization. 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...
 
NonlinearFactorGraph smootherSummarization_
 The smoother summarization on the old separator sent by the smoother during the last synchronization. More...
 
Values smootherValues_
 A temporary holding place for the linearization points of all keys being sent to the smoother. More...
 
Values theta_
 Current linearization point of all variables in the filter. More...
 

Private Member Functions

std::vector< size_tinsertFactors (const NonlinearFactorGraph &factors)
 
void moveSeparator (const FastList< Key > &keysToMove)
 
void removeFactors (const std::vector< size_t > &slots)
 
void reorder (const boost::optional< FastList< Key > > &keysToMove=boost::none)
 

Static Private Member Functions

static void optimize (const NonlinearFactorGraph &factors, Values &theta, const Ordering &ordering, VectorValues &delta, const Values &linearValues, const LevenbergMarquardtParams &parameters, Result &result)
 
template<class Container >
static void PrintKeys (const Container &keys, const std::string &indent, const std::string &title, const KeyFormatter &keyFormatter=DefaultKeyFormatter)
 Implementation of PrintKeys. More...
 
static void PrintLinearFactor (const GaussianFactor::shared_ptr &factor, const std::string &indent="", const KeyFormatter &keyFormatter=DefaultKeyFormatter)
 
static void PrintLinearFactorGraph (const GaussianFactorGraph &factors, const std::string &indent="", const std::string &title="", const KeyFormatter &keyFormatter=DefaultKeyFormatter)
 
static void PrintNonlinearFactor (const NonlinearFactor::shared_ptr &factor, const std::string &indent="", const KeyFormatter &keyFormatter=DefaultKeyFormatter)
 
static void PrintNonlinearFactorGraph (const NonlinearFactorGraph &factors, const std::string &indent="", const std::string &title="", const KeyFormatter &keyFormatter=DefaultKeyFormatter)
 
static void PrintNonlinearFactorGraph (const NonlinearFactorGraph &factors, const std::vector< size_t > &slots, const std::string &indent="", const std::string &title="", const KeyFormatter &keyFormatter=DefaultKeyFormatter)
 

Detailed Description

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

Definition at line 31 of file ConcurrentBatchFilter.h.

Member Typedef Documentation

typedef for base class

Definition at line 35 of file ConcurrentBatchFilter.h.

Definition at line 34 of file ConcurrentBatchFilter.h.

Constructor & Destructor Documentation

gtsam::ConcurrentBatchFilter::ConcurrentBatchFilter ( const LevenbergMarquardtParams parameters = LevenbergMarquardtParams())
inline

Default constructor

Definition at line 64 of file ConcurrentBatchFilter.h.

gtsam::ConcurrentBatchFilter::~ConcurrentBatchFilter ( )
inlineoverride

Default destructor

Definition at line 67 of file ConcurrentBatchFilter.h.

Member Function Documentation

Values gtsam::ConcurrentBatchFilter::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 ConcurrentBatchFilter.h.

template<class VALUE >
VALUE gtsam::ConcurrentBatchFilter::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 ConcurrentBatchFilter.h.

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

Check if two Concurrent Filters are equal

Implements gtsam::ConcurrentFilter.

Definition at line 105 of file ConcurrentBatchFilter.cpp.

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

Access the current set of deltas to the linearization point

Definition at line 91 of file ConcurrentBatchFilter.h.

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

Access the current set of factors

Definition at line 76 of file ConcurrentBatchFilter.h.

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

Access the current linearization point

Definition at line 81 of file ConcurrentBatchFilter.h.

const Ordering& gtsam::ConcurrentBatchFilter::getOrdering ( ) const
inline

Access the current ordering

Definition at line 86 of file ConcurrentBatchFilter.h.

void gtsam::ConcurrentBatchFilter::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 291 of file ConcurrentBatchFilter.cpp.

void gtsam::ConcurrentBatchFilter::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 279 of file ConcurrentBatchFilter.cpp.

std::vector< size_t > gtsam::ConcurrentBatchFilter::insertFactors ( const NonlinearFactorGraph factors)
private

Augment the graph with new factors

Parameters
factorsThe factors to add to the graph
Returns
The slots in the graph where they were inserted

Definition at line 315 of file ConcurrentBatchFilter.cpp.

void gtsam::ConcurrentBatchFilter::moveSeparator ( const FastList< Key > &  keysToMove)
private

Marginalize out the set of requested variables from the filter, caching them for the smoother This effectively moves the separator.

Parameters
keysToMoveThe set of keys to move from the filter to the smoother

Definition at line 513 of file ConcurrentBatchFilter.cpp.

void gtsam::ConcurrentBatchFilter::optimize ( const NonlinearFactorGraph factors,
Values theta,
const Ordering ordering,
VectorValues delta,
const Values linearValues,
const LevenbergMarquardtParams parameters,
ConcurrentBatchFilter::Result result 
)
staticprivate

Use a modified version of L-M to update the linearization point and delta

Definition at line 373 of file ConcurrentBatchFilter.cpp.

void gtsam::ConcurrentBatchFilter::postsync ( )
overridevirtual

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

Reimplemented from gtsam::ConcurrentFilter.

Definition at line 303 of file ConcurrentBatchFilter.cpp.

void gtsam::ConcurrentBatchFilter::presync ( )
overridevirtual

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

Reimplemented from gtsam::ConcurrentFilter.

Definition at line 192 of file ConcurrentBatchFilter.cpp.

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

Implement a GTSAM standard 'print' function

Implements gtsam::ConcurrentFilter.

Definition at line 96 of file ConcurrentBatchFilter.cpp.

template<class Container >
void gtsam::ConcurrentBatchFilter::PrintKeys ( const Container &  keys,
const std::string &  indent,
const std::string &  title,
const KeyFormatter keyFormatter = DefaultKeyFormatter 
)
staticprivate

Implementation of PrintKeys.

Print just the nonlinear keys contained inside a container

Definition at line 245 of file ConcurrentBatchFilter.h.

void gtsam::ConcurrentBatchFilter::PrintLinearFactor ( const GaussianFactor::shared_ptr factor,
const std::string &  indent = "",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
)
staticprivate

Print just the nonlinear keys in a linear factor

Definition at line 64 of file ConcurrentBatchFilter.cpp.

void gtsam::ConcurrentBatchFilter::PrintLinearFactorGraph ( const GaussianFactorGraph factors,
const std::string &  indent = "",
const std::string &  title = "",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
)
staticprivate

Print just the nonlinear keys in each linear factor for a whole Gaussian Factor Graph

Definition at line 87 of file ConcurrentBatchFilter.cpp.

void gtsam::ConcurrentBatchFilter::PrintNonlinearFactor ( const NonlinearFactor::shared_ptr factor,
const std::string &  indent = "",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
)
staticprivate

Print just the nonlinear keys in a nonlinear factor

Definition at line 27 of file ConcurrentBatchFilter.cpp.

void gtsam::ConcurrentBatchFilter::PrintNonlinearFactorGraph ( const NonlinearFactorGraph factors,
const std::string &  indent = "",
const std::string &  title = "",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
)
staticprivate

Print just the nonlinear keys in each factor for a whole Nonlinear Factor Graph

Definition at line 46 of file ConcurrentBatchFilter.cpp.

void gtsam::ConcurrentBatchFilter::PrintNonlinearFactorGraph ( const NonlinearFactorGraph factors,
const std::vector< size_t > &  slots,
const std::string &  indent = "",
const std::string &  title = "",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
)
staticprivate

Print just the nonlinear keys of specific factors in a Nonlinear Factor Graph

Definition at line 55 of file ConcurrentBatchFilter.cpp.

void gtsam::ConcurrentBatchFilter::removeFactors ( const std::vector< size_t > &  slots)
private

Remove factors from the graph by slot index

Parameters
slotsThe slots in the factor graph that should be deleted

Definition at line 343 of file ConcurrentBatchFilter.cpp.

void gtsam::ConcurrentBatchFilter::reorder ( const boost::optional< FastList< Key > > &  keysToMove = boost::none)
private

Use colamd to update into an efficient ordering

Definition at line 361 of file ConcurrentBatchFilter.cpp.

void gtsam::ConcurrentBatchFilter::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 200 of file ConcurrentBatchFilter.cpp.

ConcurrentBatchFilter::Result gtsam::ConcurrentBatchFilter::update ( const NonlinearFactorGraph newFactors = NonlinearFactorGraph(),
const Values newTheta = Values(),
const boost::optional< FastList< Key > > &  keysToMove = boost::none,
const boost::optional< std::vector< size_t > > &  removeFactorIndices = boost::none 
)
virtual

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 121 of file ConcurrentBatchFilter.cpp.

Member Data Documentation

std::queue<size_t> gtsam::ConcurrentBatchFilter::availableSlots_
protected

The set of available factor graph slots caused by deleting factors.

Definition at line 174 of file ConcurrentBatchFilter.h.

VectorValues gtsam::ConcurrentBatchFilter::delta_
protected

The current set of linear deltas from the linearization point.

Definition at line 173 of file ConcurrentBatchFilter.h.

NonlinearFactorGraph gtsam::ConcurrentBatchFilter::factors_
protected

The set of all factors currently in the filter.

Definition at line 170 of file ConcurrentBatchFilter.h.

NonlinearFactorGraph gtsam::ConcurrentBatchFilter::filterSummarization_
protected

A temporary holding place for calculated filter summarization factors to be sent to the smoother.

Definition at line 183 of file ConcurrentBatchFilter.h.

Ordering gtsam::ConcurrentBatchFilter::ordering_
protected

The current ordering used to calculate the linear deltas.

Definition at line 172 of file ConcurrentBatchFilter.h.

LevenbergMarquardtParams gtsam::ConcurrentBatchFilter::parameters_
protected

LM parameters.

Definition at line 169 of file ConcurrentBatchFilter.h.

std::vector<size_t> gtsam::ConcurrentBatchFilter::separatorSummarizationSlots_
protected

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

Definition at line 176 of file ConcurrentBatchFilter.h.

Values gtsam::ConcurrentBatchFilter::separatorValues_
protected

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

Definition at line 175 of file ConcurrentBatchFilter.h.

NonlinearFactorGraph gtsam::ConcurrentBatchFilter::smootherFactors_
protected

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

Definition at line 184 of file ConcurrentBatchFilter.h.

NonlinearFactorGraph gtsam::ConcurrentBatchFilter::smootherShortcut_
protected

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

Definition at line 180 of file ConcurrentBatchFilter.h.

NonlinearFactorGraph gtsam::ConcurrentBatchFilter::smootherSummarization_
protected

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

Definition at line 179 of file ConcurrentBatchFilter.h.

Values gtsam::ConcurrentBatchFilter::smootherValues_
protected

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

Definition at line 185 of file ConcurrentBatchFilter.h.

Values gtsam::ConcurrentBatchFilter::theta_
protected

Current linearization point of all variables in the filter.

Definition at line 171 of file ConcurrentBatchFilter.h.


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


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