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/AP_Airspeed/models/ADS_cal_EKF.m
Views: 1799
% Implementation of a simple 3-state EKF that can identify the scale1% factor that needs to be applied to a true airspeed measurement2% Paul Riseborough 27 June 201334% Inputs:5% Measured true airsped (m/s)67clear all;89% Define wind speed used for truth model10vwn_truth = 4.0;11vwe_truth = 3.0;12vwd_truth = -0.5; % convection can produce values of up to 1.5 m/s, however13% average will zero over longer periods at lower altitudes14% Slope lift will be persistent1516% Define airspeed scale factor used for truth model17K_truth = 1.2;1819% Use a 1 second time step20DT = 1.0;2122% Define the initial state error covariance matrix23% Assume initial wind uncertainty of 10 m/s and scale factor uncertainty of24% 0.225P = diag([10^2 10^2 0.001^2]);2627% Define state error growth matrix assuming wind changes at a rate of 0.128% m/s/s and scale factor drifts at a rate of 0.001 per second29Q = diag([0.1^2 0.1^2 0.001^2])*DT^2;3031% Define the initial state matrix assuming zero wind and a scale factor of32% 1.033x = [0;0;1.0];3435for i = 1:10003637%% Calculate truth values38% calculate ground velocity by simulating a wind relative39% circular path of 60m radius and 16 m/s airspeed40time = i*DT;41radius = 60;42TAS_truth = 16;43vwnrel_truth = TAS_truth*cos(TAS_truth*time/radius);44vwerel_truth = TAS_truth*sin(TAS_truth*time/radius);45vwdrel_truth = 0.0;46vgn_truth = vwnrel_truth + vwn_truth;47vge_truth = vwerel_truth + vwe_truth;48vgd_truth = vwdrel_truth + vwd_truth;4950% calculate measured ground velocity and airspeed, adding some noise and51% adding a scale factor to the airspeed measurement.52vgn_mea = vgn_truth + 0.1*rand;53vge_mea = vge_truth + 0.1*rand;54vgd_mea = vgd_truth + 0.1*rand;55TAS_mea = K_truth * TAS_truth + 0.5*rand;5657%% Perform filter processing58% This benefits from a matrix library that can handle up to 3x359% matrices6061% Perform the covariance prediction62% Q is a diagonal matrix so only need to add three terms in63% C code implementation64P = P + Q;6566% Perform the predicted measurement using the current state estimates67% No state prediction required because states are assumed to be time68% invariant plus process noise69% Ignore vertical wind component70TAS_pred = x(3) * sqrt((vgn_mea - x(1))^2 + (vge_mea - x(2))^2 + vgd_mea^2);7172% Calculate the observation Jacobian H_TAS73SH1 = (vge_mea - x(2))^2 + (vgn_mea - x(1))^2;74SH2 = 1/sqrt(SH1);75H_TAS = zeros(1,3);76H_TAS(1,1) = -(x(3)*SH2*(2*vgn_mea - 2*x(1)))/2;77H_TAS(1,2) = -(x(3)*SH2*(2*vge_mea - 2*x(2)))/2;78H_TAS(1,3) = 1/SH2;7980% Calculate the fusion innovaton covariance assuming a TAS measurement81% noise of 1.0 m/s82S = H_TAS*P*H_TAS' + 1.0; % [1 x 3] * [3 x 3] * [3 x 1] + [1 x 1]8384% Calculate the Kalman gain85KG = P*H_TAS'/S; % [3 x 3] * [3 x 1] / [1 x 1]8687% Update the states88x = x + KG*(TAS_mea - TAS_pred); % [3 x 1] + [3 x 1] * [1 x 1]8990% Update the covariance matrix91P = P - KG*H_TAS*P; % [3 x 3] *9293% force symmetry on the covariance matrix - necessary due to rounding94% errors95% Implementation will also need a further check to prevent diagonal96% terms becoming negative due to rounding errors97% This step can be made more efficient by excluding diagonal terms98% (would reduce processing by 1/3)99P = 0.5*(P + P'); % [1 x 1] * ( [3 x 3] + [3 x 3])100101%% Store results102output(i,:) = [time,x(1),x(2),x(3),vwn_truth,vwe_truth,K_truth];103104end105106%% Plot output107figure;108subplot(3,1,1);plot(output(:,1),[output(:,2),output(:,5)]);109ylabel('Wind Vel North (m/s)');110xlabel('time (sec)');111grid on;112subplot(3,1,2);plot(output(:,1),[output(:,3),output(:,6)]);113ylabel('Wind Vel East (m/s)');114xlabel('time (sec)');115grid on;116subplot(3,1,3);plot(output(:,1),[output(:,4),output(:,7)]);117ylim([0 1.5]);118ylabel('Airspeed scale factor correction');119xlabel('time (sec)');120grid on;121122123124