gtsam 4.1.1
gtsam
|
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.
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 | |
T | 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. | |
T | 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. | |
const JacobianFactor::shared_ptr | Density () const |
Return current predictive (if called after predict)/posterior (if called after update) | |
Public Types | |
typedef boost::shared_ptr< ExtendedKalmanFilter< VALUE > > | shared_ptr |
typedef VALUE | T |
typedef NoiseModelFactor2< VALUE, VALUE > | MotionFactor |
typedef NoiseModelFactor1< VALUE > | MeasurementFactor |
Static Protected Member Functions | |
static T | solve_ (const GaussianFactorGraph &linearFactorGraph, const Values &linearizationPoints, Key x, JacobianFactor::shared_ptr *newPrior) |
Protected Attributes | |
T | x_ |
JacobianFactor::shared_ptr | priorFactor_ |