root/library/bdm/estim/kalman.h @ 477

Revision 477, 12.7 kB (checked in by mido, 15 years ago)

panove, vite, jak jsem peclivej na upravu kodu.. snad se vam bude libit:) konfigurace je v souboru /system/astylerc

  • Property svn:eol-style set to native
Line 
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
16
17#include "../math/functions.h"
18#include "../stat/exp_family.h"
19#include "../math/chmat.h"
20#include "../base/user_info.h"
21
22namespace bdm {
23
24/*!
25* \brief Basic Kalman filter with full matrices (education purpose only)! Will be deleted soon!
26*/
27
28class KalmanFull {
29protected:
30        int dimx, dimy, dimu;
31        mat A, B, C, D, R, Q;
32
33        //cache
34        mat _Pp, _Ry, _iRy, _K;
35public:
36        //posterior
37        //! Mean value of the posterior density
38        vec mu;
39        //! Variance of the posterior density
40        mat P;
41
42        bool evalll;
43        double ll;
44public:
45        //! Full constructor
46        KalmanFull ( mat A, mat B, mat C, mat D, mat R, mat Q, mat P0, vec mu0 );
47        //! Here dt = [yt;ut] of appropriate dimensions
48        void bayes ( const vec &dt );
49        //! print elements of KF
50        friend std::ostream &operator<< ( std::ostream &os, const KalmanFull &kf );
51        //! For EKFfull;
52        KalmanFull() {};
53};
54
55
56/*!
57* \brief Kalman filter with covariance matrices in square root form.
58
59Parameter evolution model:\f[ x_t = A x_{t-1} + B u_t + Q^{1/2} e_t \f]
60Observation model: \f[ y_t = C x_{t-1} + C u_t + Q^{1/2} w_t. \f]
61Where $e_t$ and $w_t$ are independent vectors Normal(0,1)-distributed disturbances.
62*/
63template<class sq_T>
64
65class Kalman : public BM {
66protected:
67        //! Indetifier of output rv
68        RV rvy;
69        //! Indetifier of exogeneous rv
70        RV rvu;
71        //! cache of rv.count()
72        int dimx;
73        //! cache of rvy.count()
74        int dimy;
75        //! cache of rvu.count()
76        int dimu;
77        //! Matrix A
78        mat A;
79        //! Matrix B
80        mat B;
81        //! Matrix C
82        mat C;
83        //! Matrix D
84        mat D;
85        //! Matrix Q in square-root form
86        sq_T Q;
87        //! Matrix R in square-root form
88        sq_T R;
89
90        //!posterior density on $x_t$
91        enorm<sq_T> est;
92        //!preditive density on $y_t$
93        enorm<sq_T> fy;
94
95        //! placeholder for Kalman gain
96        mat _K;
97        //! cache of fy.mu
98        vec& _yp;
99        //! cache of fy.R
100        sq_T& _Ry;
101        //!cache of est.mu
102        vec& _mu;
103        //!cache of est.R
104        sq_T& _P;
105
106public:
107        //! Default constructor
108        Kalman ( );
109        //! Copy constructor
110        Kalman ( const Kalman<sq_T> &K0 );
111        //! Set parameters with check of relevance
112        void set_parameters ( const mat &A0, const mat &B0, const mat &C0, const mat &D0, const sq_T &Q0, const sq_T &R0 );
113        //! Set estimate values, used e.g. in initialization.
114        void set_est ( const vec &mu0, const sq_T &P0 ) {
115                sq_T pom ( dimy );
116                est.set_parameters ( mu0, P0 );
117                P0.mult_sym ( C, pom );
118                fy.set_parameters ( C*mu0, pom );
119        };
120
121        //! Here dt = [yt;ut] of appropriate dimensions
122        void bayes ( const vec &dt );
123        //!access function
124        const epdf& posterior() const {
125                return est;
126        }
127        const enorm<sq_T>* _e() const {
128                return &est;
129        }
130        //!access function
131        mat& __K() {
132                return _K;
133        }
134        //!access function
135        vec _dP() {
136                return _P->getD();
137        }
138};
139
140/*! \brief Kalman filter in square root form
141
142Trivial example:
143\include kalman_simple.cpp
144
145*/
146class KalmanCh : public Kalman<chmat> {
147protected:
148//! pre array (triangular matrix)
149        mat preA;
150//! post array (triangular matrix)
151        mat postA;
152
153public:
154        //! copy constructor
155        BM* _copy_() const {
156                KalmanCh* K = new KalmanCh;
157                K->set_parameters ( A, B, C, D, Q, R );
158                K->set_statistics ( _mu, _P );
159                return K;
160        }
161        //! Set parameters with check of relevance
162        void set_parameters ( const mat &A0, const mat &B0, const mat &C0, const mat &D0, const chmat &Q0, const chmat &R0 );
163        void set_statistics ( const vec &mu0, const chmat &P0 ) {
164                est.set_parameters ( mu0, P0 );
165        };
166
167
168        /*!\brief  Here dt = [yt;ut] of appropriate dimensions
169
170        The following equality hold::\f[
171        \left[\begin{array}{cc}
172        R^{0.5}\\
173        P_{t|t-1}^{0.5}C' & P_{t|t-1}^{0.5}CA'\\
174        & Q^{0.5}\end{array}\right]<\mathrm{orth.oper.}>=\left[\begin{array}{cc}
175        R_{y}^{0.5} & KA'\\
176        & P_{t+1|t}^{0.5}\\
177        \\\end{array}\right]\f]
178
179        Thus this object evaluates only predictors! Not filtering densities.
180        */
181        void bayes ( const vec &dt );
182};
183
184/*!
185\brief Extended Kalman Filter in full matrices
186
187An approximation of the exact Bayesian filter with Gaussian noices and non-linear evolutions of their mean.
188*/
189class EKFfull : public KalmanFull, public BM {
190protected:
191        //! Internal Model f(x,u)
192        diffbifn* pfxu;
193        //! Observation Model h(x,u)
194        diffbifn* phxu;
195
196        enorm<fsqmat> E;
197public:
198        //! Default constructor
199        EKFfull ( );
200        //! Set nonlinear functions for mean values and covariance matrices.
201        void set_parameters ( diffbifn* pfxu, diffbifn* phxu, const mat Q0, const mat R0 );
202        //! Here dt = [yt;ut] of appropriate dimensions
203        void bayes ( const vec &dt );
204        //! set estimates
205        void set_statistics ( vec mu0, mat P0 ) {
206                mu = mu0;
207                P = P0;
208        };
209        //!dummy!
210        const epdf& posterior() const {
211                return E;
212        };
213        const enorm<fsqmat>* _e() const {
214                return &E;
215        };
216        const mat _R() {
217                return P;
218        }
219};
220
221/*!
222\brief Extended Kalman Filter
223
224An approximation of the exact Bayesian filter with Gaussian noices and non-linear evolutions of their mean.
225*/
226template<class sq_T>
227class EKF : public Kalman<fsqmat> {
228        //! Internal Model f(x,u)
229        diffbifn* pfxu;
230        //! Observation Model h(x,u)
231        diffbifn* phxu;
232public:
233        //! Default constructor
234        EKF ( RV rvx, RV rvy, RV rvu );
235        //! copy constructor
236        EKF<sq_T>* _copy_() const {
237                return new EKF<sq_T> ( this );
238        }
239        //! Set nonlinear functions for mean values and covariance matrices.
240        void set_parameters ( diffbifn* pfxu, diffbifn* phxu, const sq_T Q0, const sq_T R0 );
241        //! Here dt = [yt;ut] of appropriate dimensions
242        void bayes ( const vec &dt );
243};
244
245/*!
246\brief Extended Kalman Filter in Square root
247
248An approximation of the exact Bayesian filter with Gaussian noices and non-linear evolutions of their mean.
249*/
250
251class EKFCh : public KalmanCh {
252protected:
253        //! Internal Model f(x,u)
254        diffbifn* pfxu;
255        //! Observation Model h(x,u)
256        diffbifn* phxu;
257public:
258        //! copy constructor duplicated - calls different set_parameters
259        BM* _copy_() const {
260                EKFCh* E = new EKFCh;
261                E->set_parameters ( pfxu, phxu, Q, R );
262                E->set_statistics ( _mu, _P );
263                return E;
264        }
265        //! Set nonlinear functions for mean values and covariance matrices.
266        void set_parameters ( diffbifn* pfxu, diffbifn* phxu, const chmat Q0, const chmat R0 );
267        //! Here dt = [yt;ut] of appropriate dimensions
268        void bayes ( const vec &dt );
269
270        void from_setting ( const Setting &set );
271
272        // TODO dodelat void to_setting( Setting &set ) const;
273
274};
275
276UIREGISTER ( EKFCh );
277
278
279/*!
280\brief Kalman Filter with conditional diagonal matrices R and Q.
281*/
282
283class KFcondQR : public Kalman<ldmat> {
284//protected:
285public:
286        void condition ( const vec &QR ) {
287                it_assert_debug ( QR.length() == ( dimx + dimy ), "KFcondRQ: conditioning by incompatible vector" );
288
289                Q.setD ( QR ( 0, dimx - 1 ) );
290                R.setD ( QR ( dimx, -1 ) );
291        };
292};
293
294/*!
295\brief Kalman Filter with conditional diagonal matrices R and Q.
296*/
297
298class KFcondR : public Kalman<ldmat> {
299//protected:
300public:
301        //!Default constructor
302        KFcondR ( ) : Kalman<ldmat> ( ) {};
303
304        void condition ( const vec &R0 ) {
305                it_assert_debug ( R0.length() == ( dimy ), "KFcondR: conditioning by incompatible vector" );
306
307                R.setD ( R0 );
308        };
309
310};
311
312//////// INstance
313
314template<class sq_T>
315Kalman<sq_T>::Kalman ( const Kalman<sq_T> &K0 ) : BM ( ), rvy ( K0.rvy ), rvu ( K0.rvu ),
316                dimx ( K0.dimx ), dimy ( K0.dimy ), dimu ( K0.dimu ),
317                A ( K0.A ), B ( K0.B ), C ( K0.C ), D ( K0.D ),
318                Q ( K0.Q ), R ( K0.R ),
319                est ( K0.est ), fy ( K0.fy ), _yp ( fy._mu() ), _Ry ( fy._R() ), _mu ( est._mu() ), _P ( est._R() ) {
320
321// copy values in pointers
322//      _mu = K0._mu;
323//      _P = K0._P;
324//      _yp = K0._yp;
325//      _Ry = K0._Ry;
326
327}
328
329template<class sq_T>
330Kalman<sq_T>::Kalman ( ) : BM (), est ( ), fy (),  _yp ( fy._mu() ), _Ry ( fy._R() ), _mu ( est._mu() ), _P ( est._R() ) {
331};
332
333template<class sq_T>
334void 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 ) {
335        dimx = A0.rows();
336        dimy = C0.rows();
337        dimu = B0.cols();
338
339        it_assert_debug ( A0.cols() == dimx, "Kalman: A is not square" );
340        it_assert_debug ( B0.rows() == dimx, "Kalman: B is not compatible" );
341        it_assert_debug ( C0.cols() == dimx, "Kalman: C is not square" );
342        it_assert_debug ( ( D0.rows() == dimy ) || ( D0.cols() == dimu ),       "Kalman: D is not compatible" );
343        it_assert_debug ( ( R0.cols() == dimy ) || ( R0.rows() == dimy ), "Kalman: R is not compatible" );
344        it_assert_debug ( ( Q0.cols() == dimx ) || ( Q0.rows() == dimx ), "Kalman: Q is not compatible" );
345
346        A = A0;
347        B = B0;
348        C = C0;
349        D = D0;
350        R = R0;
351        Q = Q0;
352}
353
354template<class sq_T>
355void Kalman<sq_T>::bayes ( const vec &dt ) {
356        it_assert_debug ( dt.length() == ( dimy + dimu ), "KalmanFull::bayes wrong size of dt" );
357
358        sq_T iRy ( dimy );
359        vec u = dt.get ( dimy, dimy + dimu - 1 );
360        vec y = dt.get ( 0, dimy - 1 );
361        //Time update
362        _mu = A * _mu + B * u;
363        //P  = A*P*A.transpose() + Q; in sq_T
364        _P.mult_sym ( A );
365        _P  += Q;
366
367        //Data update
368        //_Ry = C*P*C.transpose() + R; in sq_T
369        _P.mult_sym ( C, _Ry );
370        _Ry  += R;
371
372        mat Pfull = _P.to_mat();
373
374        _Ry.inv ( iRy ); // result is in _iRy;
375        _K = Pfull * C.transpose() * ( iRy.to_mat() );
376
377        sq_T pom ( ( int ) Pfull.rows() );
378        iRy.mult_sym_t ( C*Pfull, pom );
379        ( _P ) -= pom; // P = P -PC'iRy*CP;
380        ( _yp ) = C * _mu  + D * u; //y prediction
381        ( _mu ) += _K * ( y - _yp );
382
383
384        if ( evalll == true ) { //likelihood of observation y
385                ll = fy.evallog ( y );
386        }
387
388//cout << "y: " << y-(*_yp) <<" R: " << _Ry->to_mat() << " iR: " << _iRy->to_mat() << " ll: " << ll <<endl;
389
390};
391
392/*! \brief (Switching) Multiple Model
393The model runs several models in parallel and evaluates thier weights (fittness).
394
395The statistics of the resulting density are merged using (geometric?) combination.
396
397The next step is performed with the new statistics for all models.
398*/
399class MultiModel: public BM {
400protected:
401        //! List of models between which we switch
402        Array<EKFCh*> Models;
403        //! vector of model weights
404        vec w;
405        //! cache of model lls
406        vec _lls;
407        //! type of switching policy [1=maximum,2=...]
408        int policy;
409        //! internal statistics
410        enorm<chmat> est;
411public:
412        void set_parameters ( Array<EKFCh*> A, int pol0 = 1 ) {
413                Models = A;//TODO: test if evalll is set
414                w.set_length ( A.length() );
415                _lls.set_length ( A.length() );
416                policy = pol0;
417
418                est.set_rv ( RV ( "MM", A ( 0 )->posterior().dimension(), 0 ) );
419                est.set_parameters ( A ( 0 )->_e()->mean(), A ( 0 )->_e()->_R() );
420        }
421        void bayes ( const vec &dt ) {
422                int n = Models.length();
423                int i;
424                for ( i = 0; i < n; i++ ) {
425                        Models ( i )->bayes ( dt );
426                        _lls ( i ) = Models ( i )->_ll();
427                }
428                double mlls = max ( _lls );
429                w = exp ( _lls - mlls );
430                w /= sum ( w ); //normalization
431                //set statistics
432                switch ( policy ) {
433                case 1: {
434                        int mi = max_index ( w );
435                        const enorm<chmat>* st = ( Models ( mi )->_e() );
436                        est.set_parameters ( st->mean(), st->_R() );
437                }
438                break;
439                default:
440                        it_error ( "unknown policy" );
441                }
442                // copy result to all models
443                for ( i = 0; i < n; i++ ) {
444                        Models ( i )->set_statistics ( est.mean(), est._R() );
445                }
446        }
447        //all posterior densities are equal => return the first one
448        const enorm<chmat>* _e() const {
449                return &est;
450        }
451        //all posterior densities are equal => return the first one
452        const enorm<chmat>& posterior() const {
453                return est;
454        }
455
456        void from_setting ( const Setting &set );
457
458        // TODO dodelat void to_setting( Setting &set ) const;
459
460};
461
462UIREGISTER ( MultiModel );
463
464
465
466//TODO why not const pointer??
467
468template<class sq_T>
469EKF<sq_T>::EKF ( RV rvx0, RV rvy0, RV rvu0 ) : Kalman<sq_T> ( rvx0, rvy0, rvu0 ) {}
470
471template<class sq_T>
472void EKF<sq_T>::set_parameters ( diffbifn* pfxu0,  diffbifn* phxu0, const sq_T Q0, const sq_T R0 ) {
473        pfxu = pfxu0;
474        phxu = phxu0;
475
476        //initialize matrices A C, later, these will be only updated!
477        pfxu->dfdx_cond ( _mu, zeros ( dimu ), A, true );
478//      pfxu->dfdu_cond ( *_mu,zeros ( dimu ),B,true );
479        B.clear();
480        phxu->dfdx_cond ( _mu, zeros ( dimu ), C, true );
481//      phxu->dfdu_cond ( *_mu,zeros ( dimu ),D,true );
482        D.clear();
483
484        R = R0;
485        Q = Q0;
486}
487
488template<class sq_T>
489void EKF<sq_T>::bayes ( const vec &dt ) {
490        it_assert_debug ( dt.length() == ( dimy + dimu ), "KalmanFull::bayes wrong size of dt" );
491
492        sq_T iRy ( dimy, dimy );
493        vec u = dt.get ( dimy, dimy + dimu - 1 );
494        vec y = dt.get ( 0, dimy - 1 );
495        //Time update
496        _mu = pfxu->eval ( _mu, u );
497        pfxu->dfdx_cond ( _mu, u, A, false ); //update A by a derivative of fx
498
499        //P  = A*P*A.transpose() + Q; in sq_T
500        _P.mult_sym ( A );
501        _P += Q;
502
503        //Data update
504        phxu->dfdx_cond ( _mu, u, C, false ); //update C by a derivative hx
505        //_Ry = C*P*C.transpose() + R; in sq_T
506        _P.mult_sym ( C, _Ry );
507        ( _Ry ) += R;
508
509        mat Pfull = _P.to_mat();
510
511        _Ry.inv ( iRy ); // result is in _iRy;
512        _K = Pfull * C.transpose() * ( iRy.to_mat() );
513
514        sq_T pom ( ( int ) Pfull.rows() );
515        iRy.mult_sym_t ( C*Pfull, pom );
516        ( _P ) -= pom; // P = P -PC'iRy*CP;
517        _yp = phxu->eval ( _mu, u ); //y prediction
518        ( _mu ) += _K * ( y - _yp );
519
520        if ( evalll == true ) {
521                ll += fy.evallog ( y );
522        }
523};
524
525
526}
527#endif // KF_H
528
Note: See TracBrowser for help on using the browser.