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

Revision 529, 12.8 kB (checked in by vbarta, 15 years ago)

defined *_ptr wrappers of shared pointers

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