root/bdm/estim/libKF.h @ 317

Revision 317, 10.5 kB (checked in by smidl, 15 years ago)

logger cleanup

  • Property svn:eol-style set to native
RevLine 
[7]1/*!
2  \file
3  \brief Bayesian Filtering for linear Gaussian models (Kalman Filter) and extensions
4  \author Vaclav Smidl.
5
6  -----------------------------------
7  BDM++ - C++ library for Bayesian Decision Making under Uncertainty
8
9  Using IT++ for numerical operations
10  -----------------------------------
11*/
12
13#ifndef KF_H
14#define KF_H
15
[262]16
[22]17#include "../stat/libFN.h"
[28]18#include "../stat/libEF.h"
[37]19#include "../math/chmat.h"
[7]20
[283]21namespace bdm {
[7]22
23/*!
[8]24* \brief Basic Kalman filter with full matrices (education purpose only)! Will be deleted soon!
[7]25*/
[32]26
27class KalmanFull {
[62]28protected:
[7]29        int dimx, dimy, dimu;
30        mat A, B, C, D, R, Q;
[32]31
32        //cache
[7]33        mat _Pp, _Ry, _iRy, _K;
34public:
[32]35        //posterior
[7]36        //! Mean value of the posterior density
37        vec mu;
38        //! Variance of the posterior density
39        mat P;
40
[37]41        bool evalll;
42        double ll;
[7]43public:
[32]44        //! Full constructor
45        KalmanFull ( mat A, mat B, mat C, mat D, mat R, mat Q, mat P0, vec mu0 );
[7]46        //! Here dt = [yt;ut] of appropriate dimensions
[32]47        void bayes ( const vec &dt );
[33]48        //! print elements of KF
[7]49        friend std::ostream &operator<< ( std::ostream &os, const KalmanFull &kf );
[62]50        //! For EKFfull;
[283]51        KalmanFull() {};
[7]52};
53
54
55/*!
[22]56* \brief Kalman filter with covariance matrices in square root form.
[33]57
[283]58Parameter evolution model:\f[ x_t = A x_{t-1} + B u_t + Q^{1/2} e_t \f]
[33]59Observation model: \f[ y_t = C x_{t-1} + C u_t + Q^{1/2} w_t. \f]
[283]60Where $e_t$ and $w_t$ are independent vectors Normal(0,1)-distributed disturbances.
[7]61*/
62template<class sq_T>
[32]63
64class Kalman : public BM {
[22]65protected:
[33]66        //! Indetifier of output rv
[32]67        RV rvy;
[33]68        //! Indetifier of exogeneous rv
[32]69        RV rvu;
[33]70        //! cache of rv.count()
71        int dimx;
72        //! cache of rvy.count()
73        int dimy;
74        //! cache of rvu.count()
75        int dimu;
76        //! Matrix A
77        mat A;
78        //! Matrix B
[283]79        mat B;
[33]80        //! Matrix C
81        mat C;
82        //! Matrix D
83        mat D;
84        //! Matrix Q in square-root form
85        sq_T Q;
86        //! Matrix R in square-root form
87        sq_T R;
[32]88
89        //!posterior density on $x_t$
[28]90        enorm<sq_T> est;
91        //!preditive density on $y_t$
92        enorm<sq_T> fy;
[32]93
[33]94        //! placeholder for Kalman gain
[8]95        mat _K;
[33]96        //! cache of fy.mu
[83]97        vec& _yp;
[33]98        //! cache of fy.R
[83]99        sq_T& _Ry;
[33]100        //!cache of est.mu
[83]101        vec& _mu;
[33]102        //!cache of est.R
[83]103        sq_T& _P;
[32]104
[7]105public:
[22]106        //! Default constructor
[270]107        Kalman ( );
[32]108        //! Copy constructor
109        Kalman ( const Kalman<sq_T> &K0 );
110        //! Set parameters with check of relevance
[271]111        void set_parameters ( const mat &A0,const mat &B0,const mat &C0,const mat &D0,const sq_T &Q0,const sq_T &R0 );
[28]112        //! Set estimate values, used e.g. in initialization.
[32]113        void set_est ( const vec &mu0, const sq_T &P0 ) {
[283]114                sq_T pom ( dimy );
[32]115                est.set_parameters ( mu0,P0 );
[283]116                P0.mult_sym ( C,pom );
[32]117                fy.set_parameters ( C*mu0, pom );
118        };
119
[7]120        //! Here dt = [yt;ut] of appropriate dimensions
[32]121        void bayes ( const vec &dt );
[33]122        //!access function
[271]123        const epdf& posterior() const {return est;}
[200]124        const enorm<sq_T>* _e() const {return &est;}
[51]125        //!access function
126        mat& __K() {return _K;}
127        //!access function
128        vec _dP() {return _P->getD();}
[7]129};
130
[37]131/*! \brief Kalman filter in square root form
[271]132
133Trivial example:
134\include kalman_simple.cpp
[283]135
[37]136*/
[283]137class KalmanCh : public Kalman<chmat> {
[37]138protected:
139//! pre array (triangular matrix)
[283]140        mat preA;
[37]141//! post array (triangular matrix)
[283]142        mat postA;
[37]143
144public:
[283]145        //! copy constructor
146        BM* _copy_() const {
147                KalmanCh* K=new KalmanCh;
148                K->set_parameters ( A,B,C,D,Q,R );
149                K->set_statistics ( _mu,_P );
150                return K;
151        }
[37]152        //! Set parameters with check of relevance
[271]153        void set_parameters ( const mat &A0,const mat &B0,const mat &C0,const mat &D0,const chmat &Q0,const chmat &R0 );
154        void set_statistics ( const vec &mu0, const chmat &P0 ) {
[37]155                est.set_parameters ( mu0,P0 );
156        };
[283]157
158
[37]159        /*!\brief  Here dt = [yt;ut] of appropriate dimensions
[283]160
[37]161        The following equality hold::\f[
[283]162        \left[\begin{array}{cc}
163        R^{0.5}\\
164        P_{t|t-1}^{0.5}C' & P_{t|t-1}^{0.5}CA'\\
165        & Q^{0.5}\end{array}\right]<\mathrm{orth.oper.}>=\left[\begin{array}{cc}
166        R_{y}^{0.5} & KA'\\
167        & P_{t+1|t}^{0.5}\\
168        \\\end{array}\right]\f]
[37]169
[283]170        Thus this object evaluates only predictors! Not filtering densities.
[37]171        */
172        void bayes ( const vec &dt );
173};
174
[22]175/*!
[62]176\brief Extended Kalman Filter in full matrices
177
178An approximation of the exact Bayesian filter with Gaussian noices and non-linear evolutions of their mean.
179*/
180class EKFfull : public KalmanFull, public BM {
[317]181        protected:
[62]182        //! Internal Model f(x,u)
183        diffbifn* pfxu;
184        //! Observation Model h(x,u)
185        diffbifn* phxu;
[283]186
187        enorm<fsqmat> E;
[62]188public:
189        //! Default constructor
[270]190        EKFfull ( );
[62]191        //! Set nonlinear functions for mean values and covariance matrices.
192        void set_parameters ( diffbifn* pfxu, diffbifn* phxu, const mat Q0, const mat R0 );
193        //! Here dt = [yt;ut] of appropriate dimensions
194        void bayes ( const vec &dt );
195        //! set estimates
[283]196        void set_est ( vec mu0, mat P0 ) {mu=mu0;P=P0;};
[62]197        //!dummy!
[283]198        const epdf& posterior() const{return E;};
199        const enorm<fsqmat>* _e() const{return &E;};
200        const mat _R() {return P;}
[62]201};
202
203/*!
[32]204\brief Extended Kalman Filter
[22]205
206An approximation of the exact Bayesian filter with Gaussian noices and non-linear evolutions of their mean.
207*/
208template<class sq_T>
[51]209class EKF : public Kalman<fsqmat> {
[22]210        //! Internal Model f(x,u)
211        diffbifn* pfxu;
212        //! Observation Model h(x,u)
213        diffbifn* phxu;
[32]214public:
[22]215        //! Default constructor
[32]216        EKF ( RV rvx, RV rvy, RV rvu );
[283]217        //! copy constructor
218        EKF<sq_T>* _copy_() const { return new EKF<sq_T>(this); }
[33]219        //! Set nonlinear functions for mean values and covariance matrices.
[32]220        void set_parameters ( diffbifn* pfxu, diffbifn* phxu, const sq_T Q0, const sq_T R0 );
[22]221        //! Here dt = [yt;ut] of appropriate dimensions
[32]222        void bayes ( const vec &dt );
[22]223};
224
[32]225/*!
[62]226\brief Extended Kalman Filter in Square root
[37]227
228An approximation of the exact Bayesian filter with Gaussian noices and non-linear evolutions of their mean.
229*/
230
231class EKFCh : public KalmanCh {
[283]232protected:
[37]233        //! Internal Model f(x,u)
234        diffbifn* pfxu;
235        //! Observation Model h(x,u)
236        diffbifn* phxu;
237public:
[283]238        //! copy constructor duplicated - calls different set_parameters
239        BM* _copy_() const {
240                EKFCh* E=new EKFCh;
241                E->set_parameters ( pfxu,phxu,Q,R );
242                E->set_statistics ( _mu,_P );
243                return E;
244        }
[37]245        //! Set nonlinear functions for mean values and covariance matrices.
246        void set_parameters ( diffbifn* pfxu, diffbifn* phxu, const chmat Q0, const chmat R0 );
247        //! Here dt = [yt;ut] of appropriate dimensions
248        void bayes ( const vec &dt );
249};
250
251/*!
[32]252\brief Kalman Filter with conditional diagonal matrices R and Q.
253*/
254
[283]255class KFcondQR : public Kalman<ldmat> {
[32]256//protected:
257public:
[283]258        void condition ( const vec &QR ) {
259                it_assert_debug ( QR.length() == ( dimx+dimy ),"KFcondRQ: conditioning by incompatible vector" );
[32]260
[283]261                Q.setD ( QR ( 0, dimx-1 ) );
262                R.setD ( QR ( dimx, -1 ) );
263        };
[32]264};
265
266/*!
267\brief Kalman Filter with conditional diagonal matrices R and Q.
268*/
269
[283]270class KFcondR : public Kalman<ldmat> {
[32]271//protected:
272public:
[33]273        //!Default constructor
[283]274        KFcondR ( ) : Kalman<ldmat> ( ) {};
[32]275
[283]276        void condition ( const vec &R0 ) {
277                it_assert_debug ( R0.length() == ( dimy ),"KFcondR: conditioning by incompatible vector" );
278
279                R.setD ( R0 );
280        };
281
[32]282};
283
[7]284//////// INstance
285
286template<class sq_T>
[270]287Kalman<sq_T>::Kalman ( const Kalman<sq_T> &K0 ) : BM ( ),rvy ( K0.rvy ),rvu ( K0.rvu ),
288                dimx ( K0.dimx ), dimy ( K0.dimy ),dimu ( K0.dimu ),
289                A ( K0.A ), B ( K0.B ), C ( K0.C ), D ( K0.D ),
[283]290                Q ( K0.Q ), R ( K0.R ),
291                est ( K0.est ), fy ( K0.fy ), _yp ( fy._mu() ),_Ry ( fy._R() ), _mu ( est._mu() ), _P ( est._R() ) {
[32]292
[37]293// copy values in pointers
[270]294//      _mu = K0._mu;
295//      _P = K0._P;
296//      _yp = K0._yp;
297//      _Ry = K0._Ry;
[32]298
299}
300
301template<class sq_T>
[283]302Kalman<sq_T>::Kalman ( ) : BM (), est ( ), fy (),  _yp ( fy._mu() ), _Ry ( fy._R() ), _mu ( est._mu() ), _P ( est._R() ) {
[22]303};
304
305template<class sq_T>
[271]306void Kalman<sq_T>::set_parameters ( const mat &A0,const  mat &B0, const mat &C0, const mat &D0, const sq_T &Q0, const sq_T &R0 ) {
307        dimx = A0.rows();
308        dimy = C0.rows();
309        dimu = B0.cols();
[283]310
[32]311        it_assert_debug ( A0.cols() ==dimx, "Kalman: A is not square" );
312        it_assert_debug ( B0.rows() ==dimx, "Kalman: B is not compatible" );
313        it_assert_debug ( C0.cols() ==dimx, "Kalman: C is not square" );
314        it_assert_debug ( ( D0.rows() ==dimy ) || ( D0.cols() ==dimu ), "Kalman: D is not compatible" );
315        it_assert_debug ( ( R0.cols() ==dimy ) || ( R0.rows() ==dimy ), "Kalman: R is not compatible" );
316        it_assert_debug ( ( Q0.cols() ==dimx ) || ( Q0.rows() ==dimx ), "Kalman: Q is not compatible" );
[7]317
318        A = A0;
319        B = B0;
320        C = C0;
321        D = D0;
322        R = R0;
[32]323        Q = Q0;
[7]324}
325
326template<class sq_T>
[32]327void Kalman<sq_T>::bayes ( const vec &dt ) {
328        it_assert_debug ( dt.length() == ( dimy+dimu ),"KalmanFull::bayes wrong size of dt" );
[7]329
[283]330        sq_T iRy ( dimy );
[32]331        vec u = dt.get ( dimy,dimy+dimu-1 );
332        vec y = dt.get ( 0,dimy-1 );
[7]333        //Time update
[83]334        _mu = A* _mu + B*u;
[7]335        //P  = A*P*A.transpose() + Q; in sq_T
[83]336        _P.mult_sym ( A );
337        _P  +=Q;
[7]338
339        //Data update
340        //_Ry = C*P*C.transpose() + R; in sq_T
[83]341        _P.mult_sym ( C, _Ry );
342        _Ry  +=R;
[7]343
[83]344        mat Pfull = _P.to_mat();
[32]345
[83]346        _Ry.inv ( iRy ); // result is in _iRy;
347        _K = Pfull*C.transpose() * ( iRy.to_mat() );
[32]348
349        sq_T pom ( ( int ) Pfull.rows() );
[83]350        iRy.mult_sym_t ( C*Pfull,pom );
[283]351        ( _P ) -= pom; // P = P -PC'iRy*CP;
352        ( _yp ) = C* _mu  +D*u; //y prediction
353        ( _mu ) += _K* ( y- _yp );
[32]354
355
356        if ( evalll==true ) { //likelihood of observation y
[211]357                ll=fy.evallog ( y );
[7]358        }
[32]359
360//cout << "y: " << y-(*_yp) <<" R: " << _Ry->to_mat() << " iR: " << _iRy->to_mat() << " ll: " << ll <<endl;
361
[7]362};
363
[62]364
[283]365
[22]366//TODO why not const pointer??
[7]367
[22]368template<class sq_T>
[37]369EKF<sq_T>::EKF ( RV rvx0, RV rvy0, RV rvu0 ) : Kalman<sq_T> ( rvx0,rvy0,rvu0 ) {}
[28]370
371template<class sq_T>
[32]372void EKF<sq_T>::set_parameters ( diffbifn* pfxu0,  diffbifn* phxu0,const sq_T Q0,const sq_T R0 ) {
373        pfxu = pfxu0;
374        phxu = phxu0;
[7]375
[32]376        //initialize matrices A C, later, these will be only updated!
[83]377        pfxu->dfdx_cond ( _mu,zeros ( dimu ),A,true );
[33]378//      pfxu->dfdu_cond ( *_mu,zeros ( dimu ),B,true );
379        B.clear();
[83]380        phxu->dfdx_cond ( _mu,zeros ( dimu ),C,true );
[33]381//      phxu->dfdu_cond ( *_mu,zeros ( dimu ),D,true );
382        D.clear();
[22]383
[32]384        R = R0;
385        Q = Q0;
[22]386}
387
388template<class sq_T>
[32]389void EKF<sq_T>::bayes ( const vec &dt ) {
390        it_assert_debug ( dt.length() == ( dimy+dimu ),"KalmanFull::bayes wrong size of dt" );
[22]391
[283]392        sq_T iRy ( dimy,dimy );
[32]393        vec u = dt.get ( dimy,dimy+dimu-1 );
394        vec y = dt.get ( 0,dimy-1 );
[22]395        //Time update
[83]396        _mu = pfxu->eval ( _mu, u );
397        pfxu->dfdx_cond ( _mu,u,A,false ); //update A by a derivative of fx
[32]398
[22]399        //P  = A*P*A.transpose() + Q; in sq_T
[83]400        _P.mult_sym ( A );
401        _P +=Q;
[22]402
403        //Data update
[83]404        phxu->dfdx_cond ( _mu,u,C,false ); //update C by a derivative hx
[22]405        //_Ry = C*P*C.transpose() + R; in sq_T
[83]406        _P.mult_sym ( C, _Ry );
407        ( _Ry ) +=R;
[22]408
[83]409        mat Pfull = _P.to_mat();
[32]410
[83]411        _Ry.inv ( iRy ); // result is in _iRy;
412        _K = Pfull*C.transpose() * ( iRy.to_mat() );
[32]413
414        sq_T pom ( ( int ) Pfull.rows() );
[83]415        iRy.mult_sym_t ( C*Pfull,pom );
[283]416        ( _P ) -= pom; // P = P -PC'iRy*CP;
[83]417        _yp = phxu->eval ( _mu,u ); //y prediction
418        ( _mu ) += _K* ( y-_yp );
[32]419
[211]420        if ( evalll==true ) {ll+=fy.evallog ( y );}
[22]421};
422
423
[254]424}
[7]425#endif // KF_H
426
Note: See TracBrowser for help on using the browser.