#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 | |
JacobianFactor::shared_ptr | priorFactor_ |
T | x_ |
Private Member Functions | |
GTSAM_CONCEPT_ASSERT (IsTestable< VALUE >) | |
GTSAM_CONCEPT_ASSERT (IsManifold< VALUE >) | |
Standard Constructors | |
ExtendedKalmanFilter (Key key_initial, T x_initial, noiseModel::Gaussian::shared_ptr P_initial) | |
Testable | |
void | print (const std::string &s="") const |
print More... | |
Interface | |
T | predict (const NoiseModelFactor &motionFactor) |
T | update (const NoiseModelFactor &measurementFactor) |
const JacobianFactor::shared_ptr | Density () const |
Return current predictive (if called after predict)/posterior (if called after update) More... | |
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.
Definition at line 45 of file ExtendedKalmanFilter.h.
typedef std::shared_ptr<ExtendedKalmanFilter<VALUE> > gtsam::ExtendedKalmanFilter< VALUE >::shared_ptr |
Definition at line 51 of file ExtendedKalmanFilter.h.
typedef VALUE gtsam::ExtendedKalmanFilter< VALUE >::T |
Definition at line 52 of file ExtendedKalmanFilter.h.
gtsam::ExtendedKalmanFilter< VALUE >::ExtendedKalmanFilter | ( | Key | key_initial, |
T | x_initial, | ||
noiseModel::Gaussian::shared_ptr | P_initial | ||
) |
Definition at line 64 of file ExtendedKalmanFilter-inl.h.
|
inline |
Return current predictive (if called after predict)/posterior (if called after update)
Definition at line 96 of file ExtendedKalmanFilter.h.
|
private |
|
private |
ExtendedKalmanFilter< VALUE >::T gtsam::ExtendedKalmanFilter< VALUE >::predict | ( | const NoiseModelFactor & | motionFactor | ) |
Calculate predictive density The motion model should be given as a factor with key1 for and key2 for
Definition at line 79 of file ExtendedKalmanFilter-inl.h.
|
inline |
Definition at line 72 of file ExtendedKalmanFilter.h.
|
staticprotected |
Definition at line 30 of file ExtendedKalmanFilter-inl.h.
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
Definition at line 104 of file ExtendedKalmanFilter-inl.h.
|
protected |
Definition at line 56 of file ExtendedKalmanFilter.h.
|
protected |
Definition at line 55 of file ExtendedKalmanFilter.h.