#include <TinyEKF.h>
A header-only class for the Extended Kalman Filter. Your implementing class should #define the constant N and and then #include <TinyEKF.h> You will also need to implement a model() method for your application.
◆ TinyEKF()
◆ ~TinyEKF()
Deallocates memory for a TinyEKF object.
◆ getX()
| double TinyEKF::getX |
( |
int |
i | ) |
|
|
inline |
Returns the state element at a given index.
- Parameters
-
| i | the index (at least 0 and less than n |
- Returns
- state value at index
◆ model()
| virtual void TinyEKF::model |
( |
double |
fx[Nsta], |
|
|
double |
F[Nsta][Nsta], |
|
|
double |
hx[Mobs], |
|
|
double |
H[Mobs][Nsta] |
|
) |
| |
|
protectedpure virtual |
Implement this function for your EKF model.
- Parameters
-
| fx | gets output of state-transition function f(x0 .. n-1) |
| F | gets n × n Jacobian of f(x) |
| hx | gets output of observation function h(x0 .. n-1) |
| H | gets m × n Jacobian of h(x) |
Implemented in ChassisKalman, and WheelKalman.
◆ setP()
| void TinyEKF::setP |
( |
int |
i, |
|
|
int |
j, |
|
|
double |
value |
|
) |
| |
|
inlineprotected |
Sets the specified value of the prediction error covariance. Pi,j = value
- Parameters
-
| i | row index |
| j | column index |
| value | value to set |
◆ setQ()
| void TinyEKF::setQ |
( |
int |
i, |
|
|
int |
j, |
|
|
double |
value |
|
) |
| |
|
inlineprotected |
Sets the specified value of the process noise covariance. Qi,j = value
- Parameters
-
| i | row index |
| j | column index |
| value | value to set |
◆ setR()
| void TinyEKF::setR |
( |
int |
i, |
|
|
int |
j, |
|
|
double |
value |
|
) |
| |
|
inlineprotected |
Sets the specified value of the observation noise covariance. Ri,j = value
- Parameters
-
| i | row index |
| j | column index |
| value | value to set |
◆ setX()
| void TinyEKF::setX |
( |
int |
i, |
|
|
double |
value |
|
) |
| |
|
inline |
Sets the state element at a given index.
- Parameters
-
| i | the index (at least 0 and less than n |
| value | value to set |
◆ step()
| bool TinyEKF::step |
( |
double * |
z | ) |
|
|
inline |
Performs one step of the prediction and update.
- Parameters
-
| z | observation vector, length m |
- Returns
- true on success, false on failure caused by non-positive-definite matrix.
The documentation for this class was generated from the following file: