Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AC_PrecLand/PosVelEKF.h
Views: 1798
#pragma once12/*3* This class implements a simple 1-D Extended Kalman Filter to estimate the Relative body frame postion of the lading target and its relative velocity4* position and velocity of the target is predicted using delta velocity5* The predictions are corrected periodically using the landing target sensor(or camera)6*/7class PosVelEKF {8public:9// Initialize the covariance and state matrix10// This is called when the landing target is located for the first time or it was lost, then relocated11void init(float pos, float posVar, float vel, float velVar);1213// This functions runs the Prediction Step of the EKF14// This is called at 400 hz15void predict(float dt, float dVel, float dVelNoise);1617// fuse the new sensor measurement into the EKF calculations18// This is called whenever we have a new measurement available19void fusePos(float pos, float posVar);2021// Get the EKF state position22float getPos() const { return _state[0]; }2324// Get the EKF state velocity25float getVel() const { return _state[1]; }2627// get the normalized innovation squared28float getPosNIS(float pos, float posVar);2930private:31// stored covariance and state matrix3233/*34_state[0] = position35_state[1] = velocity36*/37float _state[2];3839/*40Covariance Matrix is ALWAYS symmetric, therefore the following matrix is assumed:41P = Covariance Matrix = |_cov[0] _cov[1]|42|_cov[1] _cov[2]|43*/44float _cov[3];45};464748