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.cpp
Views: 1798
#include "PosVelEKF.h"1#include <math.h>2#include <string.h>34// Initialize the covariance and state matrix5// This is called when the landing target is located for the first time or it was lost, then relocated6void PosVelEKF::init(float pos, float posVar, float vel, float velVar)7{8_state[0] = pos;9_state[1] = vel;10_cov[0] = posVar;11_cov[1] = 0.0f;12_cov[2] = velVar;13}1415// This functions runs the Prediction Step of the EKF16// This is called at 400 hz17void PosVelEKF::predict(float dt, float dVel, float dVelNoise)18{19// Newly predicted state and covariance matrix at next time step20float newState[2];21float newCov[3];2223// We assume the following state model for this problem24newState[0] = dt*_state[1] + _state[0];25newState[1] = dVel + _state[1];2627/*28The above state model is broken down into the needed EKF form:29newState = A*OldState + B*u3031Taking jacobian with respect to state, we derive the A (or F) matrix.3233A = F = |1 dt|34|0 1|3536B = |0|37|1|3839u = dVel4041Covariance Matrix is ALWAYS symmetric, therefore the following matrix is assumed:42P = Covariance Matrix = |cov[0] cov[1]|43|cov[1] cov[2]|4445newCov = F * P * F.transpose + Q46Q = |0 0 |47|0 dVelNoise^2|4849Post algebraic operations, and converting it to a upper triangular matrix (because of symmetry)50The Updated covariance matrix is of the following form:51*/5253newCov[0] = dt*_cov[1] + dt*(dt*_cov[2] + _cov[1]) + _cov[0];54newCov[1] = dt*_cov[2] + _cov[1];55newCov[2] = ((dVelNoise)*(dVelNoise)) + _cov[2];5657// store the predicted matrices58memcpy(_state,newState,sizeof(_state));59memcpy(_cov,newCov,sizeof(_cov));60}6162// fuse the new sensor measurement into the EKF calculations63// This is called whenever we have a new measurement available64void PosVelEKF::fusePos(float pos, float posVar)65{66float newState[2];67float newCov[3];6869// innovation_residual = new_sensor_readings - OldState70const float innovation_residual = pos - _state[0];7172/*73Measurement matrix H = [1 0] since we are directly measuring pos only74Innovation Covariance = S = H * P * H.Transpose + R75Since this is a 1-D measurement, R = posVar, which is expected variance in postion sensor reading76Post multiplication this becomes:77*/78const float innovation_covariance = _cov[0] + posVar;7980/*81Next step involves calculating the kalman gain "K"82K = P * H.transpose * S.inverse83After solving, this comes out to be:84K = | cov[0]/innovation_covariance |85| cov[1]/innovation_covariance |8687Updated state estimate = OldState + K * innovation residual88This is calculated and simplified below89*/9091newState[0] = _cov[0]*(innovation_residual)/(innovation_covariance) + _state[0];92newState[1] = _cov[1]*(innovation_residual)/(innovation_covariance) + _state[1];9394/*95Updated covariance matrix = (I-K*H)*P96This is calculated and simplified below. Again, this is converted to upper triangular matrix (because of symmetry)97*/9899newCov[0] = _cov[0] * posVar / innovation_covariance;100newCov[1] = _cov[1] * posVar / innovation_covariance;101newCov[2] = -_cov[1] * _cov[1] / innovation_covariance + _cov[2];102103memcpy(_state,newState,sizeof(_state));104memcpy(_cov,newCov,sizeof(_cov));105}106107// Returns normalized innovation squared108float PosVelEKF::getPosNIS(float pos, float posVar)109{110// NIS = innovation_residual.Transpose * Innovation_Covariance.Inverse * innovation_residual111const float innovation_residual = pos - _state[0];112const float innovation_covariance = _cov[0] + posVar;113114const float NIS = (innovation_residual*innovation_residual)/(innovation_covariance);115return NIS;116}117118119