ekfilter_impl.hpp

Go to the documentation of this file.
00001 // This file is part of kfilter.
00002 // kfilter is a C++ variable-dimension extended kalman filter library.
00003 //
00004 // Copyright (C) 2004        Vincent Zalzal, Sylvain Marleau
00005 // Copyright (C) 2001, 2004  Richard Gourdeau
00006 // Copyright (C) 2004        GRPR and DGE's Automation sector
00007 //                           École Polytechnique de Montréal
00008 //
00009 // Code adapted from algorithms presented in :
00010 //      Bierman, G. J. "Factorization Methods for Discrete Sequential
00011 //      Estimation", Academic Press, 1977.
00012 //
00013 // This library is free software; you can redistribute it and/or
00014 // modify it under the terms of the GNU Lesser General Public
00015 // License as published by the Free Software Foundation; either
00016 // version 2.1 of the License, or (at your option) any later version.
00017 //
00018 // This library is distributed in the hope that it will be useful,
00019 // but WITHOUT ANY WARRANTY; without even the implied warranty of
00020 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
00021 // Lesser General Public License for more details.
00022 //
00023 // You should have received a copy of the GNU Lesser General Public
00024 // License along with this library; if not, write to the Free Software
00025 // Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00026 
00027 #ifndef EKFILTER_IMPL_HPP
00028 #define EKFILTER_IMPL_HPP
00029 
00032 
00035 #define KALMAN_N_MODIFIED    1
00036 
00039 #define KALMAN_NU_MODIFIED  (1<<1)
00040 
00043 #define KALMAN_NW_MODIFIED  (1<<2)
00044 
00047 #define KALMAN_M_MODIFIED   (1<<3)
00048 
00051 #define KALMAN_NV_MODIFIED  (1<<4)
00052 
00055 #define KALMAN_P_MODIFIED   (1<<5)
00056 
00059 #define KALMAN_LOWMASK      ((1<<8) - 1)
00060 
00063 #define KALMAN_A_MODIFIED   (1<<8)
00064 
00067 #define KALMAN_W_MODIFIED   (1<<9)
00068 
00071 #define KALMAN_Q_MODIFIED   (1<<10)
00072 
00075 #define KALMAN_MIDMASK      ( ((1<<4) - 1) << 8 )
00076 
00079 #define KALMAN_H_MODIFIED   (1<<12)
00080 
00083 #define KALMAN_V_MODIFIED   (1<<13)
00084 
00087 #define KALMAN_R_MODIFIED   (1<<14)
00088 
00091 #define KALMAN_HIGHMASK     ( ((1<<4) - 1) << 12 )
00092 
00093 namespace Kalman {
00094 
00095   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00096   EKFilter<T, BEG, OQ, OVR, DBG>::EKFilter()
00097     : flags(0) {}
00098 
00099   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00100   EKFilter<T, BEG, OQ, OVR, DBG>::EKFilter(K_UINT_32 n_, K_UINT_32 nu_, 
00101                                            K_UINT_32 nw_, K_UINT_32 m_, 
00102                                            K_UINT_32 nv_)
00103     : flags(0) {
00104     setDim(n_, nu_, nw_, m_, nv_);
00105   }
00106 
00107   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00108   EKFilter<T, BEG, OQ, OVR, DBG>::~EKFilter() {}
00109 
00110   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00111   void EKFilter<T, BEG, OQ, OVR, DBG>::setDim(K_UINT_32 n_, K_UINT_32 nu_, 
00112                                               K_UINT_32 nw_, K_UINT_32 m_, 
00113                                               K_UINT_32 nv_) {
00114     setSizeX(n_);
00115     setSizeU(nu_);
00116     setSizeW(nw_);
00117     setSizeZ(m_);
00118     setSizeV(nv_);
00119   }
00120 
00121   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00122   K_UINT_32 EKFilter<T, BEG, OQ, OVR, DBG>::getSizeX() const {
00123     return n;
00124   }
00125 
00126   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00127   K_UINT_32 EKFilter<T, BEG, OQ, OVR, DBG>::getSizeU() const {
00128     return nu;
00129   }
00130 
00131   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00132   K_UINT_32 EKFilter<T, BEG, OQ, OVR, DBG>::getSizeW() const {
00133     return nw;
00134   }
00135 
00136   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00137   K_UINT_32 EKFilter<T, BEG, OQ, OVR, DBG>::getSizeZ() const {
00138     return m;
00139   }
00140 
00141   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00142   K_UINT_32 EKFilter<T, BEG, OQ, OVR, DBG>::getSizeV() const {
00143     return nv;
00144   }
00145 
00146   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00147   void EKFilter<T, BEG, OQ, OVR, DBG>::setSizeX(K_UINT_32 n_) {
00148 
00149     // verify : n_ > 0
00150 
00151     if (n_ != n) {
00152       flags |= KALMAN_N_MODIFIED;
00153       n = n_;
00154     }
00155   }
00156 
00157   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00158   void EKFilter<T, BEG, OQ, OVR, DBG>::setSizeU(K_UINT_32 nu_) {
00159     if (nu_ != nu) {
00160       flags |= KALMAN_NU_MODIFIED;
00161       nu = nu_;
00162     }
00163   }
00164 
00165   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00166   void EKFilter<T, BEG, OQ, OVR, DBG>::setSizeW(K_UINT_32 nw_) {
00167     if (nw_ != nw) {
00168       flags |= KALMAN_NW_MODIFIED;
00169       nw = nw_;
00170     }
00171   }
00172 
00173   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00174   void EKFilter<T, BEG, OQ, OVR, DBG>::setSizeZ(K_UINT_32 m_) {
00175     if (m_ != m) {
00176       flags |= KALMAN_M_MODIFIED;
00177       m = m_;
00178     }
00179   }
00180 
00181   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00182   void EKFilter<T, BEG, OQ, OVR, DBG>::setSizeV(K_UINT_32 nv_) {
00183     if (nv_ != nv) {
00184       flags |= KALMAN_NV_MODIFIED;
00185       nv = nv_;
00186     }
00187   }
00188 
00189   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00190   void EKFilter<T, BEG, OQ, OVR, DBG>::init(Vector& x_, Matrix& P_) {
00191 
00192     // verify : (x_.size() == n && P_.nrow() == n && P_.ncol() == n)
00193 
00194     x.swap(x_);
00195     _P.swap(P_);
00196     flags |= KALMAN_P_MODIFIED;
00197   }
00198 
00199   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00200   void EKFilter<T, BEG, OQ, OVR, DBG>::step(Vector& u_, const Vector& z_) {
00201     timeUpdateStep(u_);
00202     measureUpdateStep(z_);
00203   }
00204 
00205   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00206   void EKFilter<T, BEG, OQ, OVR, DBG>::timeUpdateStep(Vector& u_) {
00207 
00208     // verif : u_.size() == nu
00209     K_UINT_32 i, j, k;
00210 
00211     sizeUpdate();
00212     u.swap(u_);
00213     
00214     makeCommonProcess();
00215     makeAImpl();
00216     makeWImpl();
00217     makeQImpl();
00218     makeProcess();
00219 
00220     if (!OQ) {
00221 
00222       if (flags & KALMAN_Q_MODIFIED) {
00223 
00224         Q_ = Q;
00225         factor(Q_);
00226         upperInvert(Q_);
00227 
00228       }
00229 
00230       Q.swap(Q_);
00231       
00232       // W_ = W*U   n.nw = n.nw * nw.nw
00233 
00234       if (flags & ( KALMAN_W_MODIFIED | KALMAN_Q_MODIFIED ) ) {
00235 
00236         for (i = BEG; i < n + BEG; ++i) {
00237     
00238           for (j = BEG; j < nw + BEG; ++j) {
00239       
00240             W_(i,j) = W(i,j);
00241             for (k = BEG; k < j; ++k)
00242               W_(i,j) += W(i,k)*Q(j,k);
00243       
00244           }
00245     
00246         }
00247   
00248       }
00249       
00250       W.swap(W_);
00251   
00252     }
00253 
00254     timeUpdate();
00255 
00256     if (!OQ) {
00257       Q.swap(Q_);
00258       W.swap(W_);
00259     }
00260 
00261     u.swap(u_);
00262     flags &= ~KALMAN_MIDMASK;
00263   }
00264 
00265   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00266   void EKFilter<T, BEG, OQ, OVR, DBG>::measureUpdateStep(const Vector& z_) {
00267 
00268     // verif : z_.size() == m
00269     K_UINT_32 i, j, k;
00270 
00271     sizeUpdate();
00272 
00273     if (m == 0) {
00274       return;
00275     }
00276     
00277     makeCommonMeasure();
00278     makeHImpl();
00279     makeVImpl();
00280     makeRImpl();    
00281     makeMeasure();
00282     
00283     // verif : nv != 0
00284 
00285     for (i = BEG; i < m + BEG; ++i)
00286       dz(i) = z_(i) - z(i);
00287 
00288     makeDZ();
00289 
00290     if (OVR) {
00291 
00292       // verif : m == nv
00293 
00294       if (flags & ( KALMAN_V_MODIFIED | KALMAN_R_MODIFIED ) ) {
00295 
00296         for (i = BEG; i < m + BEG; ++i)
00297           R_(i,i) = V(i,i)*V(i,i)*R(i,i);
00298 
00299       }
00300 
00301     } else {
00302 
00303 
00304       if (flags & ( KALMAN_V_MODIFIED | KALMAN_R_MODIFIED ) ) { // calculate R_
00305 
00306         _x.resize(nv);
00307       
00308         // R_ = V*R*V'
00309         for (i = BEG; i < m + BEG; ++i) {
00310 
00311           // _x = row i of V*R = (V*R)(i,:)
00312           for (j = BEG; j < nv + BEG; ++j) {
00313 
00314             _x(j) = T(0.0);
00315             for (k = BEG; k < nv + BEG; ++k)
00316               _x(j) += V(i,k)*R(k,j);
00317 
00318           }
00319 
00320           // R_(i,:) = (V*R*V')(i,:) = (V*R)(i,:) * V'
00321           for (j = BEG; j < m + BEG; ++j) {
00322 
00323             R_(i,j) = T(0.0);
00324             for (k = BEG; k < nv + BEG; ++k)
00325               R_(i,j) += _x(k)*V(j,k);
00326 
00327           }
00328 
00329         }
00330 
00331         // R_ = U*D*U'
00332         // diag(R_) = D, upper(R_) = U, lower(R_) = junk
00333         factor(R_);
00334 
00335         // lower(R_) = (inv(U))'
00336         upperInvert(R_);
00337 
00338       }
00339 
00340       if (flags & ( KALMAN_H_MODIFIED | KALMAN_V_MODIFIED | KALMAN_R_MODIFIED ) ) { // calculate H_
00341 
00342         // H_ = inv(U)*H    m.n = m.m * m.n
00343         for (i = BEG; i < m + BEG; ++i) {
00344 
00345           for (j = BEG; j < n + BEG; ++j) {
00346 
00347             H_(i,j) = H(i,j);
00348             for (k = i + 1; k < m + BEG; ++k)
00349               H_(i,j) += R_(k,i)*H(k,j);
00350 
00351           }
00352 
00353         }
00354 
00355       }
00356 
00357       H.swap(H_);
00358 
00359       // _x = inv(U)*dz    m.1 = m.m * m.1
00360       _x.resize(m);
00361 
00362       for (i = BEG; i < m + BEG; ++i) {
00363 
00364         _x(i) = dz(i);
00365         for (k = i + 1; k < m + BEG; ++k)
00366           _x(i) += R_(k,i)*dz(k); 
00367 
00368       }
00369 
00370       dz.swap(_x);
00371 
00372     }
00373     
00374     _x.resize(n); // dx : innovation
00375     _x = T(0.0);
00376     for (i = BEG; i < m + BEG; ++i) {
00377 
00378       for (j = BEG; j < n + BEG; ++j)
00379         a(j) = H(i,j);
00380 
00381       measureUpdate(dz(i), R_(i,i));
00382 
00383     }
00384     for (i = BEG; i < n + BEG; ++i)
00385       x(i) += _x(i);
00386 
00387     if (!OVR) {
00388       H.swap(H_);
00389     }
00390 
00391     flags &= ~KALMAN_HIGHMASK;
00392   }
00393 
00394   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00395   const EKFilter<T, BEG, OQ, OVR, DBG>::Vector& EKFilter<T, BEG, OQ, OVR, DBG>::predict(Vector& u_) {
00396     
00397     // verif : u_.size() == nu
00398 
00399     sizeUpdate();
00400     u.swap(u_);   
00401     _x = x;
00402     
00403     makeCommonProcess();
00404     makeProcess();
00405     
00406     x.swap(_x);
00407     u.swap(u_);
00408     return _x;
00409   }
00410 
00411   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00412   const EKFilter<T, BEG, OQ, OVR, DBG>::Vector& EKFilter<T, BEG, OQ, OVR, DBG>::simulate() {
00413     
00414     sizeUpdate();
00415     _x = z;
00416     
00417     makeCommonMeasure();
00418     makeMeasure();
00419     
00420     z.swap(_x);
00421     return _x;
00422   }
00423 
00424   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00425   const EKFilter<T, BEG, OQ, OVR, DBG>::Vector& EKFilter<T, BEG, OQ, OVR, DBG>::getX() const {
00426     return x;
00427   }
00428 
00429   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00430   const EKFilter<T, BEG, OQ, OVR, DBG>::Matrix& EKFilter<T, BEG, OQ, OVR, DBG>::calculateP() const {
00431 
00432     if (!(flags & KALMAN_P_MODIFIED)) {
00433 
00434       _P.resize(n, n);         // keep this resize
00435     
00436       for (K_UINT_32 i = BEG; i < n + BEG; ++i) {
00437 
00438         _P(i,i) = U(i,i);
00439 
00440         for (K_UINT_32 j = i + 1; j < n + BEG; ++j) {
00441 
00442           _P(i,j)  = U(i,j)*U(j,j);
00443           _P(i,i) += U(i,j)*_P(i,j);
00444 
00445           for (K_UINT_32 k = j + 1; k < n + BEG; ++k) {
00446             _P(i,j) += U(i,k)*U(j,k)*U(k,k);
00447           }
00448 
00449           _P(j,i) = _P(i,j);
00450 
00451         }
00452 
00453       }
00454 
00455     }
00456 
00457     return _P;
00458   }
00459 
00460   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00461   void EKFilter<T, BEG, OQ, OVR, DBG>::NoModification() {
00462     modified_ = false;
00463   }
00464 
00465   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00466   void EKFilter<T, BEG, OQ, OVR, DBG>::makeBaseA() {
00467     NoModification();
00468   }
00469   
00470   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00471   void EKFilter<T, BEG, OQ, OVR, DBG>::makeBaseW() {
00472     NoModification();
00473   }
00474 
00475   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00476   void EKFilter<T, BEG, OQ, OVR, DBG>::makeBaseQ() {
00477     NoModification();
00478   }
00479   
00480   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00481   void EKFilter<T, BEG, OQ, OVR, DBG>::makeBaseH() {
00482     NoModification();
00483   }
00484 
00485   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00486   void EKFilter<T, BEG, OQ, OVR, DBG>::makeBaseV() {
00487     NoModification();
00488   }
00489 
00490   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00491   void EKFilter<T, BEG, OQ, OVR, DBG>::makeBaseR() {
00492     NoModification();
00493   }
00494 
00495   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00496   void EKFilter<T, BEG, OQ, OVR, DBG>::makeCommonProcess() {}
00497 
00498   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00499   void EKFilter<T, BEG, OQ, OVR, DBG>::makeCommonMeasure() {}
00500 
00501   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00502   void EKFilter<T, BEG, OQ, OVR, DBG>::makeA() {
00503     NoModification();
00504   }
00505   
00506   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00507   void EKFilter<T, BEG, OQ, OVR, DBG>::makeW() {
00508     NoModification();
00509   }
00510 
00511   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00512   void EKFilter<T, BEG, OQ, OVR, DBG>::makeQ() {
00513     NoModification();
00514   }
00515   
00516   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00517   void EKFilter<T, BEG, OQ, OVR, DBG>::makeH() {
00518     NoModification();
00519   }
00520 
00521   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00522   void EKFilter<T, BEG, OQ, OVR, DBG>::makeV() {
00523     NoModification();
00524   }
00525 
00526   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00527   void EKFilter<T, BEG, OQ, OVR, DBG>::makeR() {
00528     NoModification();
00529   }
00530 
00531   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00532   void EKFilter<T, BEG, OQ, OVR, DBG>::makeDZ() {}
00533 
00534   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00535   void EKFilter<T, BEG, OQ, OVR, DBG>::sizeUpdate() {
00536     
00537     if (!flags) {
00538       return;
00539     }
00540 
00541     if (flags & KALMAN_N_MODIFIED) {
00542       A.resize(n, n);
00543       makeBaseAImpl();
00544     }
00545 
00546     if (flags & (KALMAN_N_MODIFIED | KALMAN_NW_MODIFIED) ) {
00547       nn = n + nw;
00548       a.resize(nn);
00549       v.resize(nn);
00550       d.resize(nn);
00551       if (!OQ)
00552         W_.resize(n, nw);
00553       W.resize(n, nw);
00554       makeBaseWImpl();
00555     }
00556 
00557     // KALMAN_N_MODIFIED imply KALMAN_P_MODIFIED
00558     // => KALMAN_N_MODIFIED must not be set OR KALMAN_P_MODIFIED must be set
00559     // => NOT  KALMAN_N_MODIFIED  OR  KALMAN_P_MODIFIED  must be set
00560     // verif : (flags ^ KALMAN_N_MODIFIED) & 
00561     //              (KALMAN_N_MODIFIED | KALMAN_P_MODIFIED)
00562 
00563     if (flags & KALMAN_P_MODIFIED) { 
00564       // this covers the case of KALMAN_N_MODIFIED = true also
00565 
00566       // We have a new matrix P : let's factorize it and store it in U
00567       // First, resize U and copy P in its left part
00568       U.resize(n, nn);
00569       for (K_UINT_32 i = BEG; i < n + BEG; ++i)
00570         for (K_UINT_32 j = BEG; j < n + BEG; ++j)
00571           U(i,j) = _P(i,j);
00572       
00573       // Factorize
00574       factor(U);
00575 
00576     } else if (flags & KALMAN_NW_MODIFIED) {
00577       // KALMAN_N_MODIFIED is necessarily false, else KALMAN_P_MODIFIED
00578       // would have been true
00579 
00580       // Let's just copy U in temporary matrix _P of the right size,
00581       // then swap the matrices
00582       _P.resize(n, nn);
00583       for (K_UINT_32 i = BEG; i < n + BEG; ++i)
00584         for (K_UINT_32 j = i; j < n + BEG; ++j)
00585           _P(i,j) = U(i,j);
00586       U.swap(_P);
00587     }
00588 
00589     if (flags & KALMAN_NW_MODIFIED) {
00590       if (!OQ)
00591         Q_.resize(nw, nw);
00592       Q.resize(nw, nw);
00593       makeBaseQImpl();
00594     }
00595 
00596     if (m != 0) {
00597 
00598       if (flags & (KALMAN_N_MODIFIED | KALMAN_M_MODIFIED) ) {
00599         if (!OVR)
00600           H_.resize(m, n);
00601         H.resize(m, n);
00602         makeBaseHImpl();
00603       }
00604 
00605       if (flags & (KALMAN_M_MODIFIED | KALMAN_NV_MODIFIED) ) {
00606         V.resize(m, nv);
00607         makeBaseVImpl();
00608       }
00609 
00610       if (flags & KALMAN_NV_MODIFIED) {
00611         R.resize(nv, nv);
00612         makeBaseRImpl();
00613       }
00614 
00615       if (flags & KALMAN_M_MODIFIED) {
00616         R_.resize(m, m);
00617         z.resize(m);
00618         dz.resize(m);
00619       }
00620 
00621     }
00622     
00623     flags &= ~KALMAN_LOWMASK;
00624   }
00625 
00626   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00627   void EKFilter<T, BEG, OQ, OVR, DBG>::factor(Matrix& P_) {
00628 
00629     // ne pas vérifier que P_.ncol() == P_.nrow(), comme ça, même si
00630     // nrow() < ncol(), on peut factoriser la sous-matrice carrée de P
00631     // Utile pour factoriser U
00632 
00633     T alpha, beta;
00634     K_UINT_32 i, j, k, N = P_.nrow();
00635     for(j = N - 1 + BEG; j > BEG; --j) {
00636       alpha = T(1.0)/P_(j,j);
00637       for(k = BEG; k < j; ++k) {
00638         beta = P_(k,j);
00639         P_(k,j) = alpha*beta;
00640         for(i = BEG; i <= k; ++i)
00641           P_(i,k) -= beta*P_(i,j);
00642       }
00643     }
00644   }
00645 
00646   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00647   void EKFilter<T, BEG, OQ, OVR, DBG>::upperInvert(Matrix& P_) {
00648 
00649     T val;
00650     K_UINT_32 i, j, k, N = P_.nrow();
00651     for (i = N - 2 + BEG; i >= BEG; --i) {
00652       for (k = i + 1; k < N + BEG; ++k) {
00653 
00654         val = P_(i,k);
00655         for (j = i + 1; j <= k - 1; ++j)
00656           val += P_(i,j)*P_(k,j);
00657         P_(k,i) = -val;
00658 
00659       }
00660     }
00661 
00662   }
00663 
00664   // U    u     U-D covariance matrix (n,nn)
00665   // A    phi   transition matrix (F) (n,n)
00666   // W    g     process noise matrix (G) (n,nw)
00667   // Q    q     process noise variance vector (nw) Q = diag(q)
00668   // a, v, d temporary vectors
00669   // U is updated
00670   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00671   void EKFilter<T, BEG, OQ, OVR, DBG>::timeUpdate() {
00672 
00673     K_UINT_32 i, j, k;
00674     T sigma, dinv;
00675   
00676     // U = phi * U
00677     // d = diag(U)
00678     // 
00679     // This algo could be faster
00680     // if phi is known to be diagonal
00681     // It could be almost zapped if phi=I
00682     for(j = n - 1 + BEG; j > BEG; --j) {
00683       for(i = BEG; i <= j; ++i)
00684         d(i) = U(i,j);
00685       for(i = BEG; i < n + BEG; ++i) {
00686         U(i,j) = A(i,j);
00687         for(k = BEG; k < j; ++k)
00688           U(i,j) += A(i,k)*d(k);
00689       }
00690     }
00691 
00692     d(BEG) = U(BEG,BEG);
00693     for(j = BEG; j < n + BEG; ++j)
00694       U(j,BEG) = A(j,BEG);
00695 
00696     // d(n+1:nn) = q 
00697     // U(:,n+1:nn) = G 
00698     for(i = BEG; i < nw + BEG; ++i) {
00699       d(i+n) = Q(i,i);
00700       for(j = BEG; j < n + BEG; ++j)
00701         U(j,i+n) = W(j,i);
00702     }
00703 
00704     // Gram-Schmidt
00705     // Too hard to simplify
00706     for(j = n - 1 + BEG; j >= BEG; --j) {
00707       sigma = T(0.0);
00708       for(k = BEG; k < nn + BEG; ++k) {
00709         v(k) = U(j,k);
00710         a(k) = d(k)*v(k);
00711         sigma += v(k)*a(k);
00712       }
00713       U(j,j) = sigma;
00714       if(j == BEG || sigma == T(0.0)) continue;
00715       dinv = T(1.0)/sigma;
00716       for(k = BEG; k < j; ++k) {
00717         sigma = T(0.0);
00718         for(i = BEG; i < nn + BEG; ++i) 
00719           sigma += U(k,i)*a(i);
00720         sigma *= dinv;
00721         for(i = BEG; i < nn + BEG; ++i) 
00722           U(k,i) -= sigma*v(i);
00723         U(j,k) = sigma;
00724       }
00725     }
00726 
00727     // U = transpose(U)
00728     for(j = BEG + 1; j < n + BEG; ++j)
00729       for(i = BEG; i < j; ++i)
00730         U(i,j) = U(j,i);
00731   }
00732 
00733   // x     a priori estimate vector (n)
00734   // U     a priori U-D covariance matrix (n,nn)
00735   // dz    measurement diff (z - ax) (scalar)
00736   // a     measurement coefficients vector (n) (a row of A, which is H)
00737   //          a is destroyed
00738   // r     measurement variance
00739   // d is a temporary vector
00740   // x and U are updated
00741   // a is destroyed
00742   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00743   void EKFilter<T, BEG, OQ, OVR, DBG>::measureUpdate(T dz, T r) {
00744 
00745     K_UINT_32 i, j, k;
00746     T alpha, gamma, beta, lambda;
00747 
00748     // dz = dz - Hdx
00749     for (j = BEG; j < n + BEG; ++j)
00750       dz -= a(j)*_x(j);
00751     
00752     // d = D * transpose(U) * a
00753     // a =     transpose(U) * a
00754     //
00755     // This algo could be faster
00756     // if A is known to be diagonal or I
00757     for(j = n - 1 + BEG; j > BEG; --j) {
00758       for(k = BEG; k < j; ++k)
00759         a(j) += U(k,j)*a(k);
00760       d(j) = U(j,j)*a(j);
00761     }
00762     d(BEG) = U(BEG,BEG)*a(BEG);
00763 
00764     // UDU
00765     // Too hard to simplify
00766     alpha = r+d(BEG)*a(BEG);
00767     gamma = T(1.0)/alpha;
00768     U(BEG,BEG) = r*gamma*U(BEG,BEG);
00769     for(j = BEG + 1; j < n + BEG; ++j) {
00770       beta = alpha;
00771       alpha += d(j)*a(j);
00772       lambda = -a(j)*gamma;
00773       gamma = T(1.0)/alpha;
00774       U(j,j) *= beta*gamma;
00775       for(i = BEG; i < j; ++i) {
00776         beta = U(i,j);
00777         U(i,j) = beta+d(i)*lambda;
00778         d(i) += d(j)*beta;
00779       }
00780     }
00781   
00782     // dx = dx + K(dz - Hdx)
00783     dz *= gamma;
00784     for(j = BEG; j < n + BEG; ++j)
00785       _x(j) += d(j)*dz;
00786   }
00787 
00788   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00789   void EKFilter<T, BEG, OQ, OVR, DBG>::makeBaseAImpl() {
00790     modified_ = true;
00791     makeBaseA();
00792     if (modified_)
00793       flags |= KALMAN_A_MODIFIED;
00794   }
00795   
00796   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00797   void EKFilter<T, BEG, OQ, OVR, DBG>::makeBaseWImpl() {
00798     modified_ = true;
00799     makeBaseW();
00800     if (modified_)
00801       flags |= KALMAN_W_MODIFIED;    
00802   }
00803   
00804   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00805   void EKFilter<T, BEG, OQ, OVR, DBG>::makeBaseQImpl() {
00806     modified_ = true;
00807     makeBaseQ();
00808     if (modified_)
00809       flags |= KALMAN_Q_MODIFIED;    
00810   }
00811   
00812   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00813   void EKFilter<T, BEG, OQ, OVR, DBG>::makeBaseHImpl() {
00814     modified_ = true;
00815     makeBaseH();
00816     if (modified_)
00817       flags |= KALMAN_H_MODIFIED;    
00818   }
00819   
00820   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00821   void EKFilter<T, BEG, OQ, OVR, DBG>::makeBaseVImpl() {
00822     modified_ = true;
00823     makeBaseV();
00824     if (modified_)
00825       flags |= KALMAN_V_MODIFIED;    
00826   }
00827   
00828   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00829   void EKFilter<T, BEG, OQ, OVR, DBG>::makeBaseRImpl() {
00830     modified_ = true;
00831     makeBaseR();
00832     if (modified_)
00833       flags |= KALMAN_R_MODIFIED;    
00834   }
00835   
00836   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00837   void EKFilter<T, BEG, OQ, OVR, DBG>::makeAImpl() {
00838     modified_ = true;
00839     makeA();
00840     if (modified_)
00841       flags |= KALMAN_A_MODIFIED;    
00842   }
00843   
00844   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00845   void EKFilter<T, BEG, OQ, OVR, DBG>::makeWImpl() {
00846     modified_ = true;
00847     makeW();
00848     if (modified_)
00849       flags |= KALMAN_W_MODIFIED;    
00850   }
00851   
00852   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00853   void EKFilter<T, BEG, OQ, OVR, DBG>::makeQImpl() {
00854     modified_ = true;
00855     makeQ();
00856     if (modified_)
00857       flags |= KALMAN_Q_MODIFIED;    
00858   }
00859   
00860   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00861   void EKFilter<T, BEG, OQ, OVR, DBG>::makeHImpl() {
00862     modified_ = true;
00863     makeH();
00864     if (modified_)
00865       flags |= KALMAN_H_MODIFIED;    
00866   }
00867   
00868   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00869   void EKFilter<T, BEG, OQ, OVR, DBG>::makeVImpl() {
00870     modified_ = true;
00871     makeV();
00872     if (modified_)
00873       flags |= KALMAN_V_MODIFIED;    
00874   }
00875 
00876   template<typename T, K_UINT_32 BEG, bool OQ, bool OVR, bool DBG>
00877   void EKFilter<T, BEG, OQ, OVR, DBG>::makeRImpl() {
00878     modified_ = true;
00879     makeR();
00880     if (modified_)
00881       flags |= KALMAN_R_MODIFIED;    
00882   }
00883 
00884 }
00885 
00886 #endif

Generated on Sat Jan 28 21:02:01 2006 for KFilter by  doxygen 1.4.5