UWB-Tracking
Loading...
Searching...
No Matches
Public Member Functions | Private Member Functions | Private Attributes | List of all members
EKF_Filter Class Reference

Extended Kalman Filter (EKF) class for state estimation. More...

#include <extended-kalman.h>

Public Member Functions

 EKF_Filter ()
 Default constructor for the EKF_Filter class. Initializes the EKF and reads the Anchor positions from EEPROM. More...
 
 ~EKF_Filter ()
 Destructor of Kalman-Filter Object, cleanup recources. More...
 
Matrix< double, DIM_X, 1 > & vecX ()
 Get the estimated state vector. More...
 
const Matrix< double, DIM_X, 1 > & vecX () const
 Get the estimated state vector (const version). More...
 
Matrix< double, DIM_X, DIM_X > & matP ()
 Get the state covariance matrix. More...
 
const Matrix< double, DIM_X, DIM_X > & matP () const
 Get the state covariance matrix (const version). More...
 
void predict (const Matrix< double, DIM_X, DIM_X > &matF, const Matrix< double, DIM_X, DIM_X > &matQ)
 Perform the prediction step of the EKF. More...
 
void correct (const Matrix< double, DIM_Z, 1 > &vecZ, const Matrix< double, DIM_Z, DIM_Z > &matR, const Matrix< double, DIM_Z, DIM_X > &matH)
 Perform the correction step of the EKF. More...
 
template<typename PredictionModelCallback >
void predictEkf (PredictionModelCallback predictionModel, const Matrix< double, DIM_X, DIM_X > &matJacobF, const Matrix< double, DIM_X, DIM_X > &matQ)
 Perform the prediction step of the EKF using a user-defined prediction model. More...
 
template<typename MeasurementModelCallback >
void correctEkf (MeasurementModelCallback measurementModel, const Matrix< double, DIM_Z, 1 > &vecZ, const Matrix< double, DIM_Z, DIM_Z > &matR, const Matrix< double, DIM_Z, DIM_X > &matJcobH)
 Perform the correction step of the EKF using a user-defined measurement model. More...
 

Private Member Functions

void read_landmarks_from_eeprom (void)
 state covariance matrix More...
 

Private Attributes

Matrix< double, DIM_X, 1 > m_vecX { Matrix<double, DIM_X, 1>::Zero() }
 
Matrix< double, DIM_X, DIM_Xm_matP { Matrix<double, DIM_X, DIM_X>::Zero() }
 estimated state vector More...
 

Detailed Description

Extended Kalman Filter (EKF) class for state estimation.

Constructor & Destructor Documentation

◆ EKF_Filter()

Default constructor for the EKF_Filter class. Initializes the EKF and reads the Anchor positions from EEPROM.

◆ ~EKF_Filter()

~EKF_Filter ( )
inline

Destructor of Kalman-Filter Object, cleanup recources.

Member Function Documentation

◆ correct()

void correct ( const Matrix< double, DIM_Z, 1 > &  vecZ,
const Matrix< double, DIM_Z, DIM_Z > &  matR,
const Matrix< double, DIM_Z, DIM_X > &  matH 
)
inline

Perform the correction step of the EKF.

Parameters
vecZThe measurement vector.
matRThe measurement noise covariance matrix.
matHThe measurement Jacobian matrix.

◆ correctEkf()

void correctEkf ( MeasurementModelCallback  measurementModel,
const Matrix< double, DIM_Z, 1 > &  vecZ,
const Matrix< double, DIM_Z, DIM_Z > &  matR,
const Matrix< double, DIM_Z, DIM_X > &  matJcobH 
)
inline

Perform the correction step of the EKF using a user-defined measurement model.

Template Parameters
MeasurementModelCallbackThe type of the measurement model callback function.
Parameters
measurementModelThe measurement model callback function.
vecZThe measurement vector.
matRThe measurement noise covariance matrix.
matJcobHThe measurement Jacobian matrix.

◆ matP() [1/2]

Matrix< double, DIM_X, DIM_X > & matP ( )
inline

Get the state covariance matrix.

Returns
Reference to the state covariance matrix.

◆ matP() [2/2]

const Matrix< double, DIM_X, DIM_X > & matP ( ) const
inline

Get the state covariance matrix (const version).

Returns
Const reference to the state covariance matrix.

◆ predict()

void predict ( const Matrix< double, DIM_X, DIM_X > &  matF,
const Matrix< double, DIM_X, DIM_X > &  matQ 
)
inline

Perform the prediction step of the EKF.

Parameters
matFThe state transition matrix.
matQThe process noise covariance matrix.

◆ predictEkf()

void predictEkf ( PredictionModelCallback  predictionModel,
const Matrix< double, DIM_X, DIM_X > &  matJacobF,
const Matrix< double, DIM_X, DIM_X > &  matQ 
)
inline

Perform the prediction step of the EKF using a user-defined prediction model.

Template Parameters
PredictionModelCallbackThe type of the prediction model callback function.
Parameters
predictionModelThe prediction model callback function.
matJacobFThe Jacobian matrix of the prediction model.
matQThe process noise covariance matrix.

◆ read_landmarks_from_eeprom()

void read_landmarks_from_eeprom ( void  )
private

state covariance matrix

Reads landmarks from EEPROM and stores them in the landmarkPositions matrix.

◆ vecX() [1/2]

Matrix< double, DIM_X, 1 > & vecX ( )
inline

Get the estimated state vector.

Returns
Reference to the estimated state vector.

◆ vecX() [2/2]

const Matrix< double, DIM_X, 1 > & vecX ( ) const
inline

Get the estimated state vector (const version).

Returns
Const reference to the estimated state vector.

Member Data Documentation

◆ m_matP

Matrix<double, DIM_X, DIM_X> m_matP { Matrix<double, DIM_X, DIM_X>::Zero() }
private

estimated state vector

◆ m_vecX

Matrix<double, DIM_X, 1> m_vecX { Matrix<double, DIM_X, 1>::Zero() }
private

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