GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
Public Types | Static Protected Member Functions | Protected Attributes | List of all members
gtsam::ExtendedKalmanFilter< VALUE > Class Template Reference

#include <ExtendedKalmanFilter.h>

Public Types

typedef std::shared_ptr< ExtendedKalmanFilter< VALUE > > shared_ptr
 
typedef VALUE T
 

Static Protected Member Functions

static T solve_ (const GaussianFactorGraph &linearFactorGraph, const Values &linearizationPoints, Key x, JacobianFactor::shared_ptr *newPrior)
 

Protected Attributes

x_
 
JacobianFactor::shared_ptr priorFactor_
 

Standard Constructors

 ExtendedKalmanFilter (Key key_initial, T x_initial, noiseModel::Gaussian::shared_ptr P_initial)
 

Testable

void print (const std::string &s="") const
 print
 

Interface

predict (const NoiseModelFactor &motionFactor)
 
update (const NoiseModelFactor &measurementFactor)
 
const JacobianFactor::shared_ptr Density () const
 Return current predictive (if called after predict)/posterior (if called after update)
 

Detailed Description

template<class VALUE>
class gtsam::ExtendedKalmanFilter< VALUE >

This is a generic Extended Kalman Filter class implemented using nonlinear factors. GTSAM basically does SRIF with Cholesky to solve the filter problem, making this an efficient, numerically stable Kalman Filter implementation.

The Kalman Filter relies on two models: a motion model that predicts the next state using the current state, and a measurement model that predicts the measurement value at a given state. Because these two models are situation-dependent, base classes for each have been provided above, from which the user must derive a class and incorporate the actual modeling equations.

The class provides a "predict" and "update" function to perform these steps independently. TODO: a "predictAndUpdate" that combines both steps for some computational savings.

Member Function Documentation

◆ predict()

template<class VALUE >
ExtendedKalmanFilter< VALUE >::T gtsam::ExtendedKalmanFilter< VALUE >::predict ( const NoiseModelFactor motionFactor)

Calculate predictive density \( P(x_) ~ \int P(x_min) P(x_min, x_)\) The motion model should be given as a factor with key1 for \(x_min\) and key2 for \(x_\)

◆ update()

template<class VALUE >
ExtendedKalmanFilter< VALUE >::T gtsam::ExtendedKalmanFilter< VALUE >::update ( const NoiseModelFactor measurementFactor)

Calculate posterior density P(x_) ~ L(z|x) P(x) The likelihood L(z|x) should be given as a unary factor on x


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