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

Revision 536, 12.7 kB (checked in by smidl, 15 years ago)

removal of unused functions _e() and samplecond(,) and added documentation lines

  • 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        //!access function
128        mat& __K() {
129                return _K;
130        }
131        //!access function
132        vec _dP() {
133                return _P->getD();
134        }
135};
136
137/*! \brief Kalman filter in square root form
138
139Trivial example:
140\include kalman_simple.cpp
141
142*/
143class KalmanCh : public Kalman<chmat> {
144protected:
145//! pre array (triangular matrix)
146        mat preA;
147//! post array (triangular matrix)
148        mat postA;
149
150public:
151        //! copy constructor
152        BM* _copy_() const {
153                KalmanCh* K = new KalmanCh;
154                K->set_parameters ( A, B, C, D, Q, R );
155                K->set_statistics ( _mu, _P );
156                return K;
157        }
158        //! Set parameters with check of relevance
159        void set_parameters ( const mat &A0, const mat &B0, const mat &C0, const mat &D0, const chmat &Q0, const chmat &R0 );
160        void set_statistics ( const vec &mu0, const chmat &P0 ) {
161                est.set_parameters ( mu0, P0 );
162        };
163
164
165        /*!\brief  Here dt = [yt;ut] of appropriate dimensions
166
167        The following equality hold::\f[
168        \left[\begin{array}{cc}
169        R^{0.5}\\
170        P_{t|t-1}^{0.5}C' & P_{t|t-1}^{0.5}CA'\\
171        & Q^{0.5}\end{array}\right]<\mathrm{orth.oper.}>=\left[\begin{array}{cc}
172        R_{y}^{0.5} & KA'\\
173        & P_{t+1|t}^{0.5}\\
174        \\\end{array}\right]\f]
175
176        Thus this object evaluates only predictors! Not filtering densities.
177        */
178        void bayes ( const vec &dt );
179};
180
181/*!
182\brief Extended Kalman Filter in full matrices
183
184An approximation of the exact Bayesian filter with Gaussian noices and non-linear evolutions of their mean.
185*/
186class EKFfull : public KalmanFull, public BM {
187protected:
188        //! Internal Model f(x,u)
189        shared_ptr<diffbifn> pfxu;
190
191        //! Observation Model h(x,u)
192        shared_ptr<diffbifn> phxu;
193
194        enorm<fsqmat> E;
195public:
196        //! Default constructor
197        EKFfull ( );
198
199        //! Set nonlinear functions for mean values and covariance matrices.
200        void set_parameters ( const shared_ptr<diffbifn> &pfxu, const shared_ptr<diffbifn> &phxu, const mat Q0, const mat R0 );
201
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 mat _R() {
214                return P;
215        }
216};
217
218/*!
219\brief Extended Kalman Filter
220
221An approximation of the exact Bayesian filter with Gaussian noices and non-linear evolutions of their mean.
222*/
223template<class sq_T>
224class EKF : public Kalman<fsqmat> {
225        //! Internal Model f(x,u)
226        diffbifn* pfxu;
227        //! Observation Model h(x,u)
228        diffbifn* phxu;
229public:
230        //! Default constructor
231        EKF ( RV rvx, RV rvy, RV rvu );
232        //! copy constructor
233        EKF<sq_T>* _copy_() const {
234                return new EKF<sq_T> ( this );
235        }
236        //! Set nonlinear functions for mean values and covariance matrices.
237        void set_parameters ( diffbifn* pfxu, diffbifn* phxu, const sq_T Q0, const sq_T R0 );
238        //! Here dt = [yt;ut] of appropriate dimensions
239        void bayes ( const vec &dt );
240};
241
242/*!
243\brief Extended Kalman Filter in Square root
244
245An approximation of the exact Bayesian filter with Gaussian noices and non-linear evolutions of their mean.
246*/
247
248class EKFCh : public KalmanCh {
249protected:
250        //! Internal Model f(x,u)
251        shared_ptr<diffbifn> pfxu;
252
253        //! Observation Model h(x,u)
254        shared_ptr<diffbifn> phxu;
255public:
256        //! copy constructor duplicated - calls different set_parameters
257        BM* _copy_() const {
258                EKFCh* E = new EKFCh;
259                E->set_parameters ( pfxu, phxu, Q, R );
260                E->set_statistics ( _mu, _P );
261                return E;
262        }
263        //! Set nonlinear functions for mean values and covariance matrices.
264        void set_parameters ( const shared_ptr<diffbifn> &pfxu, const shared_ptr<diffbifn> &phxu, const chmat Q0, const chmat R0 );
265
266        //! Here dt = [yt;ut] of appropriate dimensions
267        void bayes ( const vec &dt );
268
269        void from_setting ( const Setting &set );
270
271        // TODO dodelat void to_setting( Setting &set ) const;
272
273        const enorm<chmat>& posterior() {return est;}
274};
275
276UIREGISTER ( EKFCh );
277SHAREDPTR ( EKFCh );
278
279
280/*!
281\brief Kalman Filter with conditional diagonal matrices R and Q.
282*/
283
284class KFcondQR : public Kalman<ldmat> {
285//protected:
286public:
287        void condition ( const vec &QR ) {
288                it_assert_debug ( QR.length() == ( dimx + dimy ), "KFcondRQ: conditioning by incompatible vector" );
289
290                Q.setD ( QR ( 0, dimx - 1 ) );
291                R.setD ( QR ( dimx, -1 ) );
292        };
293};
294
295/*!
296\brief Kalman Filter with conditional diagonal matrices R and Q.
297*/
298
299class KFcondR : public Kalman<ldmat> {
300//protected:
301public:
302        //!Default constructor
303        KFcondR ( ) : Kalman<ldmat> ( ) {};
304
305        void condition ( const vec &R0 ) {
306                it_assert_debug ( R0.length() == ( dimy ), "KFcondR: conditioning by incompatible vector" );
307
308                R.setD ( R0 );
309        };
310
311};
312
313//////// INstance
314
315template<class sq_T>
316Kalman<sq_T>::Kalman ( const Kalman<sq_T> &K0 ) : BM ( ), rvy ( K0.rvy ), rvu ( K0.rvu ),
317                dimx ( K0.dimx ), dimy ( K0.dimy ), dimu ( K0.dimu ),
318                A ( K0.A ), B ( K0.B ), C ( K0.C ), D ( K0.D ),
319                Q ( K0.Q ), R ( K0.R ),
320                est ( K0.est ), fy ( K0.fy ), _yp ( fy._mu() ), _Ry ( fy._R() ), _mu ( est._mu() ), _P ( est._R() ) {
321
322// copy values in pointers
323//      _mu = K0._mu;
324//      _P = K0._P;
325//      _yp = K0._yp;
326//      _Ry = K0._Ry;
327
328}
329
330template<class sq_T>
331Kalman<sq_T>::Kalman ( ) : BM (), est ( ), fy (),  _yp ( fy._mu() ), _Ry ( fy._R() ), _mu ( est._mu() ), _P ( est._R() ) {
332};
333
334template<class sq_T>
335void 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 ) {
336        dimx = A0.rows();
337        dimy = C0.rows();
338        dimu = B0.cols();
339
340        it_assert_debug ( A0.cols() == dimx, "Kalman: A is not square" );
341        it_assert_debug ( B0.rows() == dimx, "Kalman: B is not compatible" );
342        it_assert_debug ( C0.cols() == dimx, "Kalman: C is not square" );
343        it_assert_debug ( ( D0.rows() == dimy ) || ( D0.cols() == dimu ),       "Kalman: D is not compatible" );
344        it_assert_debug ( ( R0.cols() == dimy ) || ( R0.rows() == dimy ), "Kalman: R is not compatible" );
345        it_assert_debug ( ( Q0.cols() == dimx ) || ( Q0.rows() == dimx ), "Kalman: Q is not compatible" );
346
347        A = A0;
348        B = B0;
349        C = C0;
350        D = D0;
351        R = R0;
352        Q = Q0;
353}
354
355template<class sq_T>
356void Kalman<sq_T>::bayes ( const vec &dt ) {
357        it_assert_debug ( dt.length() == ( dimy + dimu ), "KalmanFull::bayes wrong size of dt" );
358
359        sq_T iRy ( dimy );
360        vec u = dt.get ( dimy, dimy + dimu - 1 );
361        vec y = dt.get ( 0, dimy - 1 );
362        //Time update
363        _mu = A * _mu + B * u;
364        //P  = A*P*A.transpose() + Q; in sq_T
365        _P.mult_sym ( A );
366        _P  += Q;
367
368        //Data update
369        //_Ry = C*P*C.transpose() + R; in sq_T
370        _P.mult_sym ( C, _Ry );
371        _Ry  += R;
372
373        mat Pfull = _P.to_mat();
374
375        _Ry.inv ( iRy ); // result is in _iRy;
376        _K = Pfull * C.transpose() * ( iRy.to_mat() );
377
378        sq_T pom ( ( int ) Pfull.rows() );
379        iRy.mult_sym_t ( C*Pfull, pom );
380        ( _P ) -= pom; // P = P -PC'iRy*CP;
381        ( _yp ) = C * _mu  + D * u; //y prediction
382        ( _mu ) += _K * ( y - _yp );
383
384
385        if ( evalll == true ) { //likelihood of observation y
386                ll = fy.evallog ( y );
387        }
388
389//cout << "y: " << y-(*_yp) <<" R: " << _Ry->to_mat() << " iR: " << _iRy->to_mat() << " ll: " << ll <<endl;
390
391};
392
393/*! \brief (Switching) Multiple Model
394The model runs several models in parallel and evaluates thier weights (fittness).
395
396The statistics of the resulting density are merged using (geometric?) combination.
397
398The next step is performed with the new statistics for all models.
399*/
400class MultiModel: public BM {
401protected:
402        //! List of models between which we switch
403        Array<EKFCh*> Models;
404        //! vector of model weights
405        vec w;
406        //! cache of model lls
407        vec _lls;
408        //! type of switching policy [1=maximum,2=...]
409        int policy;
410        //! internal statistics
411        enorm<chmat> est;
412public:
413        void set_parameters ( Array<EKFCh*> A, int pol0 = 1 ) {
414                Models = A;//TODO: test if evalll is set
415                w.set_length ( A.length() );
416                _lls.set_length ( A.length() );
417                policy = pol0;
418
419                est.set_rv ( RV ( "MM", A ( 0 )->posterior().dimension(), 0 ) );
420                est.set_parameters ( A ( 0 )->posterior().mean(), A ( 0 )->posterior()._R() );
421        }
422        void bayes ( const vec &dt ) {
423                int n = Models.length();
424                int i;
425                for ( i = 0; i < n; i++ ) {
426                        Models ( i )->bayes ( dt );
427                        _lls ( i ) = Models ( i )->_ll();
428                }
429                double mlls = max ( _lls );
430                w = exp ( _lls - mlls );
431                w /= sum ( w ); //normalization
432                //set statistics
433                switch ( policy ) {
434                case 1: {
435                        int mi = max_index ( w );
436                        const enorm<chmat> &st = Models ( mi )->posterior() ;
437                        est.set_parameters ( st.mean(), st._R() );
438                }
439                break;
440                default:
441                        it_error ( "unknown policy" );
442                }
443                // copy result to all models
444                for ( i = 0; i < n; i++ ) {
445                        Models ( i )->set_statistics ( est.mean(), est._R() );
446                }
447        }
448        //! posterior density
449        const enorm<chmat>& posterior() const {
450                return est;
451        }
452
453        void from_setting ( const Setting &set );
454
455        // TODO dodelat void to_setting( Setting &set ) const;
456
457};
458
459UIREGISTER ( MultiModel );
460SHAREDPTR ( MultiModel );
461
462
463
464//TODO why not const pointer??
465
466template<class sq_T>
467EKF<sq_T>::EKF ( RV rvx0, RV rvy0, RV rvu0 ) : Kalman<sq_T> ( rvx0, rvy0, rvu0 ) {}
468
469template<class sq_T>
470void EKF<sq_T>::set_parameters ( diffbifn* pfxu0,  diffbifn* phxu0, const sq_T Q0, const sq_T R0 ) {
471        pfxu = pfxu0;
472        phxu = phxu0;
473
474        //initialize matrices A C, later, these will be only updated!
475        pfxu->dfdx_cond ( _mu, zeros ( dimu ), A, true );
476//      pfxu->dfdu_cond ( *_mu,zeros ( dimu ),B,true );
477        B.clear();
478        phxu->dfdx_cond ( _mu, zeros ( dimu ), C, true );
479//      phxu->dfdu_cond ( *_mu,zeros ( dimu ),D,true );
480        D.clear();
481
482        R = R0;
483        Q = Q0;
484}
485
486template<class sq_T>
487void EKF<sq_T>::bayes ( const vec &dt ) {
488        it_assert_debug ( dt.length() == ( dimy + dimu ), "KalmanFull::bayes wrong size of dt" );
489
490        sq_T iRy ( dimy, dimy );
491        vec u = dt.get ( dimy, dimy + dimu - 1 );
492        vec y = dt.get ( 0, dimy - 1 );
493        //Time update
494        _mu = pfxu->eval ( _mu, u );
495        pfxu->dfdx_cond ( _mu, u, A, false ); //update A by a derivative of fx
496
497        //P  = A*P*A.transpose() + Q; in sq_T
498        _P.mult_sym ( A );
499        _P += Q;
500
501        //Data update
502        phxu->dfdx_cond ( _mu, u, C, false ); //update C by a derivative hx
503        //_Ry = C*P*C.transpose() + R; in sq_T
504        _P.mult_sym ( C, _Ry );
505        ( _Ry ) += R;
506
507        mat Pfull = _P.to_mat();
508
509        _Ry.inv ( iRy ); // result is in _iRy;
510        _K = Pfull * C.transpose() * ( iRy.to_mat() );
511
512        sq_T pom ( ( int ) Pfull.rows() );
513        iRy.mult_sym_t ( C*Pfull, pom );
514        ( _P ) -= pom; // P = P -PC'iRy*CP;
515        _yp = phxu->eval ( _mu, u ); //y prediction
516        ( _mu ) += _K * ( y - _yp );
517
518        if ( evalll == true ) {
519                ll += fy.evallog ( y );
520        }
521};
522
523
524}
525#endif // KF_H
526
Note: See TracBrowser for help on using the browser.