ukf.m
上传用户:hfch80
上传日期:2007-10-25
资源大小:3637k
文件大小:5k
源码类别:

行业发展研究

开发平台:

Matlab

  1. function [xEst,PEst,xPred,PPred,zPred,inovation,S,K]=ukf(xEst,PEst,U,Q,ffun,z,R,hfun,dt,alpha,beta,kappa);
  2. % TITLE    :  UNSCENTED KALMAN FILTER  
  3. %
  4. % PURPOSE  :  This function performs one complete step of the unscented Kalman filter.
  5. %
  6. % SYNTAX   :  [xEst,PEst,xPred,PPred,zPred,inovation]=ukf(xEst,PEst,U,Q,ffun,z,R,hfun,dt,alpha,beta,kappa)
  7. %
  8. % INPUTS   :  - xEst             : state mean estimate at time k  
  9. %             - PEst             : state covariance at time k
  10. %             - U                : vector of control inputs
  11. %             - Q                : process noise covariance at time k  
  12. %             - z                : observation at k+1  
  13. %             - R                : measurement noise covariance at k+1  
  14. %             - ffun             : process model function  
  15. %             - hfun             : observation model function  
  16. %             - dt               : time step (passed to ffun/hfun)   
  17. %       - alpha (optional) : sigma point scaling parameter. Defaults to 1.
  18. %             - beta  (optional) : higher order error scaling parameter. Default to 0.  
  19. %             - kappa (optional) : scalar tuning parameter 1. Defaults to 0.  
  20. %
  21. % OUTPUTS  :  - xEst             : updated estimate of state mean at time k+1
  22. %       - PEst             : updated state covariance at time k+1
  23. %             - xPred            : prediction of state mean at time k+1
  24. %             - PPred            : prediction of state covariance at time k+1
  25. %       - inovation        : innovation vector
  26. %  
  27. % AUTHORS  :  Simon J. Julier       (sjulier@erols.com)    1998-2000
  28. %             Rudolph van der Merwe (rvdmerwe@ece.ogi.edu) 2000
  29. %
  30. % DATE     :  14 August 2000
  31. %
  32. % NOTES    :  The process model is of the form, x(k+1) = ffun[x(k),v(k),dt,u(k)]
  33. %             where v(k) is the process noise vector. The observation model is 
  34. %             of the form, z(k) = hfun[x(k),w(k),dt,u(k)], where w(k) is the 
  35. %             observation noise vector.
  36. %
  37. %             This code was written to be readable. There is significant
  38. %             scope for optimisation even in Matlab.
  39. %
  40.   
  41. % Process defaults
  42. if (nargin < 10)
  43.   alpha=1;
  44. end;
  45. if (nargin < 11)
  46.   beta=0;
  47. end;
  48. if (nargin < 12)
  49.   kappa=0;
  50. end;
  51. % Calculate the dimensions of the problem and a few useful
  52. % scalars
  53. states       = size(xEst(:),1);
  54. observations = size(z(:),1);
  55. vNoise       = size(Q,2);
  56. wNoise       = size(R,2);
  57. noises       = vNoise+wNoise;
  58. % Augment the state vector with the noise vectors.
  59. % Note: For simple, additive noise models this part
  60. % can be done differently to save on computational cost.
  61. % For details, contact Rudolph v.d. Merwe
  62. if (noises)
  63.   N=[Q zeros(vNoise,wNoise); zeros(wNoise,vNoise) R];
  64.   PQ=[PEst zeros(states,noises);zeros(noises,states) N];
  65.   xQ=[xEst;zeros(noises,1)];
  66. else
  67.   PQ=PEst;
  68.   xQ=xEst;
  69. end;
  70. % Calculate the sigma points and there corresponding weights using the Scaled Unscented
  71. % Transformation
  72. [xSigmaPts, wSigmaPts, nsp] = scaledSymmetricSigmaPoints(xQ, PQ, alpha, beta, kappa); 
  73. % Duplicate wSigmaPts into matrix for code speedup
  74. wSigmaPts_xmat = repmat(wSigmaPts(:,2:nsp),states,1);
  75. wSigmaPts_zmat = repmat(wSigmaPts(:,2:nsp),observations,1);
  76. % Work out the projected sigma points and their means
  77. % This routine is fairly generic. The only thing to watch out for are
  78. % angular discontinuities. There is a standard trick for doing this -
  79. % contact me (Julier) for details!
  80. xPredSigmaPts = feval(ffun,xSigmaPts(1:states,:),repmat(U(:),1,nsp),xSigmaPts(states+1:states+vNoise,:),dt);
  81. zPredSigmaPts = feval(hfun,xPredSigmaPts,repmat(U(:),1,nsp),xSigmaPts(states+vNoise+1:states+noises,:),dt);
  82. % Calculate the mean. Based on discussions with C. Schaefer, form
  83. % is chosen to maximise numerical robustness.
  84. % - I vectorized this part of the code for a speed increase : RvdM 2000
  85. xPred = sum(wSigmaPts_xmat .* (xPredSigmaPts(:,2:nsp) - repmat(xPredSigmaPts(:,1),1,nsp-1)),2);
  86. zPred = sum(wSigmaPts_zmat .* (zPredSigmaPts(:,2:nsp) - repmat(zPredSigmaPts(:,1),1,nsp-1)),2);
  87. xPred=xPred+xPredSigmaPts(:,1);
  88. zPred=zPred+zPredSigmaPts(:,1);
  89. % Work out the covariances and the cross correlations. Note that
  90. % the weight on the 0th point is different from the mean
  91. % calculation due to the scaled unscented algorithm.
  92. exSigmaPt = xPredSigmaPts(:,1)-xPred;
  93. ezSigmaPt = zPredSigmaPts(:,1)-zPred;
  94. PPred   = wSigmaPts(nsp+1)*exSigmaPt*exSigmaPt';
  95. PxzPred = wSigmaPts(nsp+1)*exSigmaPt*ezSigmaPt';
  96. S       = wSigmaPts(nsp+1)*ezSigmaPt*ezSigmaPt';
  97. exSigmaPt = xPredSigmaPts(:,2:nsp) - repmat(xPred,1,nsp-1);
  98. ezSigmaPt = zPredSigmaPts(:,2:nsp) - repmat(zPred,1,nsp-1);
  99. PPred     = PPred + (wSigmaPts_xmat .* exSigmaPt) * exSigmaPt';
  100. S         = S + (wSigmaPts_zmat .* ezSigmaPt) * ezSigmaPt';
  101. PxzPred   = PxzPred + exSigmaPt * (wSigmaPts_zmat .* ezSigmaPt)';
  102. %%%%% MEASUREMENT UPDATE
  103. % Calculate Kalman gain
  104. K  = PxzPred / S;
  105. % Calculate Innovation
  106. inovation = z - zPred;
  107. % Update mean
  108. xEst = xPred + K*inovation;
  109. % Update covariance
  110. PEst = PPred - K*S*K';