UWB-Tracking
|
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_X > | m_matP { Matrix<double, DIM_X, DIM_X>::Zero() } |
estimated state vector More... | |
Extended Kalman Filter (EKF) class for state estimation.
EKF_Filter | ( | ) |
Default constructor for the EKF_Filter class. Initializes the EKF and reads the Anchor positions from EEPROM.
|
inline |
Destructor of Kalman-Filter Object, cleanup recources.
|
inline |
Perform the correction step of the EKF.
vecZ | The measurement vector. |
matR | The measurement noise covariance matrix. |
matH | The measurement Jacobian matrix. |
|
inline |
Perform the correction step of the EKF using a user-defined measurement model.
MeasurementModelCallback | The type of the measurement model callback function. |
measurementModel | The measurement model callback function. |
vecZ | The measurement vector. |
matR | The measurement noise covariance matrix. |
matJcobH | The measurement Jacobian matrix. |
Get the state covariance matrix.
Get the state covariance matrix (const version).
|
inline |
Perform the prediction step of the EKF.
matF | The state transition matrix. |
matQ | The process noise covariance matrix. |
|
inline |
Perform the prediction step of the EKF using a user-defined prediction model.
PredictionModelCallback | The type of the prediction model callback function. |
predictionModel | The prediction model callback function. |
matJacobF | The Jacobian matrix of the prediction model. |
matQ | The process noise covariance matrix. |
|
private |
state covariance matrix
Reads landmarks from EEPROM and stores them in the landmarkPositions matrix.
|
inline |
Get the estimated state vector.
|
inline |
Get the estimated state vector (const version).
estimated state vector