Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes
alvar::Kalman Class Reference

Kalman implementation. More...

#include <Kalman.h>

Inheritance diagram for alvar::Kalman:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 Kalman (int _n)
 Constructor.
CvMat * predict (unsigned long tick)
 Predict the Kalman state vector for the given time step This calls updateF for updating the transition matrix based on the real time step.
CvMat * predict_update (KalmanSensor *sensor, unsigned long tick)
 Predict the Kalman state vector for the given time step and update the state using the Kalman gain.
double seconds_since_update (unsigned long tick)
 Helper method.
virtual void update_F (unsigned long tick)
 ~Kalman ()
 Destructor.

Public Attributes

CvMat * P
 The error covariance matrix describing the accuracy of the state estimate.
CvMat * P_pred
 The predicted error covariance matrix.
CvMat * Q
 The covariance matrix for the process noise.

Protected Member Functions

void predict_P ()

Protected Attributes

int prev_tick

Detailed Description

Kalman implementation.

The Kalman filter provides an effective way of estimating a system/process recursively (http://www.cs.unc.edu/~welch/media/pdf/kalman_intro.pdf). In this implementation we have separated the Kalman class (KalmanCore, Kalman or KalmanEkf) from the sensor class (KalmanSensorCore, KalmanSensor or KalmanSensorEkf). The selected Kalman class contains always the latest estimation of the process. The estimation can be updated using one or several sensors. This implementation allows SCAAT approach, where there may be several sensors (and several controls) for each Kalman filter (See http://www.cs.unc.edu/~welch/scaat.html).

Currently we have have three levels of implementations for both Kalman and Sensor (core, "normal" and EKF).

The core implementations can be used for really fast bare-bones core implementations when we have precalculated and constant K. In systems where F, H, Q and R are constants the K will converge into a constant and it can be precalculated. Note, that the core implementation need to assume constant frame rate if F depends on the timestep between frames. Note also, that the core-classes cannot use EKF Jacobians because they change the H.

The "normal" implementations are used when we have a linear F for Kalman, or linear H for KalmanSensor. The EKF implementations are used when we have non-linear function f() for KalmanEkf, or non-linear function h() for KalmanSensorEkf.

Furthermore we have a class KalmanVisualize for visualizing the internal state of Kalman.

Note, that now the KalmanControl is left out from this implementation. But it could be added using similar conventions as the KalmanSensor.

Examples:
SampleFilter.cpp.

Definition at line 178 of file Kalman.h.


Constructor & Destructor Documentation

alvar::Kalman::Kalman ( int  _n)

Constructor.

Parameters:
nThe number of items in the Kalman state vector
_mThe number of measurements given by this sensor

Definition at line 161 of file Kalman.cpp.

Destructor.

Definition at line 168 of file Kalman.cpp.


Member Function Documentation

CvMat * alvar::Kalman::predict ( unsigned long  tick)

Predict the Kalman state vector for the given time step This calls updateF for updating the transition matrix based on the real time step.

x_pred = F*x P_pred = F*P*trans(F) + Q

Definition at line 178 of file Kalman.cpp.

void alvar::Kalman::predict_P ( ) [protected]

Definition at line 153 of file Kalman.cpp.

CvMat * alvar::Kalman::predict_update ( KalmanSensor sensor,
unsigned long  tick 
)

Predict the Kalman state vector for the given time step and update the state using the Kalman gain.

  • Calls first the predict to ensure that the prediction is based on same timestep as the update
  • K = P_pred * trans(H) * inv(H*P_pred*trans(H) + R)
  • x = x_pred + K* ( z - H*x_pred)
  • P = (I - K*H) * P_pred

Definition at line 185 of file Kalman.cpp.

double alvar::Kalman::seconds_since_update ( unsigned long  tick)

Helper method.

Definition at line 195 of file Kalman.cpp.

void alvar::Kalman::update_F ( unsigned long  tick) [virtual]

If your transition matrix F is based on time you need to override this method.

Reimplemented in alvar::KalmanEkf.

Definition at line 174 of file Kalman.cpp.


Member Data Documentation

The error covariance matrix describing the accuracy of the state estimate.

Definition at line 184 of file Kalman.h.

The predicted error covariance matrix.

Definition at line 188 of file Kalman.h.

int alvar::Kalman::prev_tick [protected]

Definition at line 180 of file Kalman.h.

The covariance matrix for the process noise.

Definition at line 186 of file Kalman.h.


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


ar_track_alvar
Author(s): Scott Niekum
autogenerated on Thu Jun 6 2019 21:12:55