constantVelocityEKFilter Class Reference

Constant velocity Kalman filter. More...

#include <mht_types.h>

List of all members.

Public Member Functions

void InitFilter (Vector4d &x_init, Matrix4d &P_init)
void InitFilter (Vector4d &x_init)
 Init filter.
void SetIdentity (kMatrix &M, int size, double value=1)
 Set a matrix to identity.
void SetZero (kMatrix &M, int size)
 Set a matrix to zero.

Public Attributes

Vector3d inovation_error
int life_time
int miss_associations
Vector4d x_predicted
Vector3d z_measured

Protected Member Functions

void makeA ()
 Make the process Jacobian matrix.
void makeBaseA ()
 Make the base constant process Jacobian matrix.
void makeBaseH ()
 Make measurement sensitivity matrix.
void makeBaseV ()
 Make measurement noise sensitivity matrix.
void makeBaseW ()
 Make process noise sensitivity matrix.
void makeCommonProcess ()
 This function is called before all other make something functions.
void makeMeasure ()
 Make measurement, used when measurement is not possible (i'm not using it now).
void makeProcess ()
 Make process, model iteration.
void makeQ ()
 Make process noise covariance matrix.
void makeR ()
 Make measurement noise covariance matrix.

Protected Attributes

double dt
 Time interval between measurements.
Time lt
 Time of the last call to the makeCommonProcess function.

Detailed Description

Constant velocity Kalman filter.

This class implements a constant velocity Kalman filter on two variables (x,y).
This filter is linear and should use KFilter instead of EKFilter, but this way its easier to expand.

\[ X = \left[ \begin{array}{c} x \\ \\ y\\ \\ \dot x \\ \\ \dot y \end{array} \right ] \]

...

Definition at line 103 of file mht_types.h.


Member Function Documentation

void constantVelocityEKFilter::InitFilter ( Vector4d &  x_init,
Matrix4d &  P_init 
)

Definition at line 84 of file mht_types.cpp.

void constantVelocityEKFilter::InitFilter ( Vector4d &  x_init  ) 

Init filter.

Inits the filter with a start vector

Parameters:
x_init start position of the filter

Definition at line 54 of file mht_types.cpp.

void constantVelocityEKFilter::makeA (  )  [protected]

Make the process Jacobian matrix.

Definition at line 159 of file mht_types.cpp.

void constantVelocityEKFilter::makeBaseA (  )  [protected]

Make the base constant process Jacobian matrix.

Definition at line 136 of file mht_types.cpp.

void constantVelocityEKFilter::makeBaseH (  )  [protected]

Make measurement sensitivity matrix.

Definition at line 165 of file mht_types.cpp.

void constantVelocityEKFilter::makeBaseV (  )  [protected]

Make measurement noise sensitivity matrix.

Definition at line 178 of file mht_types.cpp.

void constantVelocityEKFilter::makeBaseW (  )  [protected]

Make process noise sensitivity matrix.

Definition at line 173 of file mht_types.cpp.

void constantVelocityEKFilter::makeCommonProcess (  )  [protected]

This function is called before all other make something functions.

It's currently being used to update the time interval between iterations (dt).

Definition at line 131 of file mht_types.cpp.

void constantVelocityEKFilter::makeMeasure (  )  [protected]

Make measurement, used when measurement is not possible (i'm not using it now).

Definition at line 338 of file mht_types.cpp.

void constantVelocityEKFilter::makeProcess (  )  [protected]

Make process, model iteration.

Definition at line 326 of file mht_types.cpp.

void constantVelocityEKFilter::makeQ (  )  [protected]

Make process noise covariance matrix.

Definition at line 290 of file mht_types.cpp.

void constantVelocityEKFilter::makeR (  )  [protected]

Make measurement noise covariance matrix.

Definition at line 183 of file mht_types.cpp.

void constantVelocityEKFilter::SetIdentity ( kMatrix M,
int  size,
double  value = 1 
)

Set a matrix to identity.

Set diagonal elements to 1 or the input parameter value and all others to 0.
This function only works properly in square matrices.

Parameters:
M matrix to set
size size of the matrix, this should not be needed, i'll remove it in a further expansion
value optional value for the diagonal elements, default is 1
void constantVelocityEKFilter::SetZero ( kMatrix M,
int  size 
)

Set a matrix to zero.

Set all elements of a matrix to zero.
This function only works properly in square matrices.

Parameters:
M matrix to set
size size of the matrix, this should not be needed, i'll remove it in a further expansion

Member Data Documentation

double constantVelocityEKFilter::dt [protected]

Time interval between measurements.

Definition at line 148 of file mht_types.h.

Definition at line 143 of file mht_types.h.

Definition at line 139 of file mht_types.h.

Time constantVelocityEKFilter::lt [protected]

Time of the last call to the makeCommonProcess function.

Definition at line 150 of file mht_types.h.

Definition at line 138 of file mht_types.h.

Definition at line 141 of file mht_types.h.

Definition at line 142 of file mht_types.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


mtt
Author(s): Jorge Almeida
autogenerated on Wed Jul 23 04:34:58 2014