gtsam  4.0.0
gtsam
gtsam::IncrementalFixedLagSmoother Class Reference

Detailed Description

This is a base class for the various HMF2 implementations.

The HMF2 eliminates the factor graph such that the active states are placed in/near the root. This base class implements a function to calculate the ordering, and an update function to incorporate new factors into the HMF.

+ Inheritance diagram for gtsam::IncrementalFixedLagSmoother:

Public Member Functions

 IncrementalFixedLagSmoother (double smootherLag=0.0, const ISAM2Params &parameters=ISAM2Params())
 default constructor
 
virtual ~IncrementalFixedLagSmoother ()
 destructor
 
virtual void print (const std::string &s="IncrementalFixedLagSmoother:\n", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
 Print the factor for debugging and testing (implementing Testable)
 
virtual bool equals (const FixedLagSmoother &rhs, double tol=1e-9) const
 Check if two IncrementalFixedLagSmoother Objects are equal.
 
Result update (const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const KeyTimestampMap &timestamps=KeyTimestampMap(), const FastVector< size_t > &factorsToRemove=FactorIndices())
 Add new factors, updating the solution and re-linearizing as needed. More...
 
Values calculateEstimate () const
 Compute an estimate from the incomplete linear delta computed during the last update. More...
 
template<class VALUE >
VALUE calculateEstimate (Key key) const
 Compute an estimate for a single variable using its incomplete linear delta computed during the last update. More...
 
const ISAM2Paramsparams () const
 return the current set of iSAM2 parameters
 
const NonlinearFactorGraphgetFactors () const
 Access the current set of factors.
 
const ValuesgetLinearizationPoint () const
 Access the current linearization point.
 
const VectorValuesgetDelta () const
 Access the current set of deltas to the linearization point.
 
Matrix marginalCovariance (Key key) const
 Calculate marginal covariance on given variable.
 
const ISAM2ResultgetISAM2Result () const
 Get results of latest isam2 update.
 

Public Types

typedef boost::shared_ptr< IncrementalFixedLagSmoothershared_ptr
 Typedef for a shared pointer to an Incremental Fixed-Lag Smoother.
 

Protected Member Functions

void eraseKeysBefore (double timestamp)
 Erase any keys associated with timestamps before the provided time.
 
void createOrderingConstraints (const KeyVector &marginalizableKeys, boost::optional< FastMap< Key, int > > &constrainedKeys) const
 Fill in an iSAM2 ConstrainedKeys structure such that the provided keys are eliminated before all others.
 

Protected Attributes

ISAM2 isam_
 An iSAM2 object used to perform inference. More...
 
ISAM2Result isamResult_
 Store results of latest isam2 update.
 

Member Function Documentation

◆ calculateEstimate() [1/2]

Values gtsam::IncrementalFixedLagSmoother::calculateEstimate ( ) const
inlinevirtual

Compute an estimate from the incomplete linear delta computed during the last update.

This delta is incomplete because it was not updated below wildfire_threshold. If only a single variable is needed, it is faster to call calculateEstimate(const KEY&).

Implements gtsam::FixedLagSmoother.

◆ calculateEstimate() [2/2]

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

Compute an estimate for a single variable using its incomplete linear delta computed during the last update.

This is faster than calling the no-argument version of calculateEstimate, which operates on all variables.

Parameters
key
Returns

◆ update()

FixedLagSmoother::Result gtsam::IncrementalFixedLagSmoother::update ( const NonlinearFactorGraph newFactors = NonlinearFactorGraph(),
const Values newTheta = Values(),
const KeyTimestampMap timestamps = KeyTimestampMap(),
const FastVector< size_t > &  factorsToRemove = FactorIndices() 
)
virtual

Add new factors, updating the solution and re-linearizing as needed.

Parameters
newFactorsnew factors on old and/or new variables
newThetanew values for new variables only
timestampsan (optional) map from keys to real time stamps
factorsToRemovean (optional) list of factors to remove.

Implements gtsam::FixedLagSmoother.

Member Data Documentation

◆ isam_

ISAM2 gtsam::IncrementalFixedLagSmoother::isam_
protected

An iSAM2 object used to perform inference.

The smoother lag is controlled by what factors are removed each iteration


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