TR-mbed 1.0
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
TinyEKF Class Referenceabstract

#include <TinyEKF.h>

Inheritance diagram for TinyEKF:
ChassisKalman WheelKalman

Public Member Functions

double getX (int i)
 
void setX (int i, double value)
 
bool step (double *z)
 

Protected Member Functions

 TinyEKF ()
 
 ~TinyEKF ()
 
virtual void model (double fx[Nsta], double F[Nsta][Nsta], double hx[Mobs], double H[Mobs][Nsta])=0
 
void setP (int i, int j, double value)
 
void setQ (int i, int j, double value)
 
void setR (int i, int j, double value)
 

Protected Attributes

double * x
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ TinyEKF()

TinyEKF::TinyEKF ( )
inlineprotected

Initializes a TinyEKF object.

◆ ~TinyEKF()

TinyEKF::~TinyEKF ( )
inlineprotected

Deallocates memory for a TinyEKF object.

Member Function Documentation

◆ getX()

double TinyEKF::getX ( int  i)
inline

Returns the state element at a given index.

Parameters
ithe 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
fxgets output of state-transition function f(x0 .. n-1)
Fgets n × n Jacobian of f(x)
hxgets output of observation function h(x0 .. n-1)
Hgets 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
irow index
jcolumn index
valuevalue 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
irow index
jcolumn index
valuevalue 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
irow index
jcolumn index
valuevalue to set

◆ setX()

void TinyEKF::setX ( int  i,
double  value 
)
inline

Sets the state element at a given index.

Parameters
ithe index (at least 0 and less than n
valuevalue to set

◆ step()

bool TinyEKF::step ( double *  z)
inline

Performs one step of the prediction and update.

Parameters
zobservation vector, length m
Returns
true on success, false on failure caused by non-positive-definite matrix.

Member Data Documentation

◆ x

double* TinyEKF::x
protected

The current state.


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