UWB-Tracking
|
Classes | |
class | EKF_Filter |
Extended Kalman Filter (EKF) class for state estimation. More... | |
Functions | |
Matrix< double, DIM_X, 1 > | predictionModel (const Matrix< double, DIM_X, 1 > ¤tState) |
Prediction model for the Extended Kalman Filter (EKF). More... | |
Matrix< double, DIM_Z, DIM_X > | calculateJacobianMatrix (const Matrix< double, DIM_X, 1 > &vecX) |
Calculate the Jacobian matrix for the measurement model. More... | |
Matrix< double, DIM_Z, 1 > | calculateMeasurement (const Matrix< double, DIM_X, 1 > ¤tPosition) |
Calculate the measurement vector. More... | |
Variables | |
static uint32_t | lastTime = millis() |
static Matrix< double, DIM_X, 1 > | x_kminus1 = (Eigen::Matrix<double, DIM_X, 1>() << 0.0, 0.0, 0.0).finished() |
static Matrix< double, NUM_LANDMARKS, 3 > | landmarkPositions { Matrix<double, NUM_LANDMARKS, 3>::Zero() } |
Calculate the Jacobian matrix for the measurement model.
vecX | The state vector. |
Matrix< double, DIM_Z, 1 > calculateMeasurement | ( | const Matrix< double, DIM_X, 1 > & | currentPosition | ) |
Calculate the measurement vector.
currentPosition | The current position. |
Prediction model for the Extended Kalman Filter (EKF).
currentState | The current state vector. |
|
static |
|
static |