covFlt.hpp

Go to the documentation of this file.
00001 #ifndef _BAYES_FILTER_COVARIANCE
00002 #define _BAYES_FILTER_COVARIANCE
00003 
00004 /*
00005  * Bayes++ the Bayesian Filtering Library
00006  * Copyright (c) 2002 Michael Stevens
00007  * See accompanying Bayes++.htm for terms and conditions of use.
00008  *
00009  * $Id: covFlt.hpp 562 2006-04-05 20:46:23 +0200 (Wed, 05 Apr 2006) mistevens $
00010  */
00011 
00012 /*
00013  * Covariance Filter Scheme.
00014  *  Implemention of extended Kalman filter
00015  * 
00016  * To work with with Linear and Linrz models
00017  *  a) a state seperate from covariance predict is used.
00018  *  b) a EKF innovation update algorithm is used.
00019  * Discontinous observe models require that predict is normailised with
00020  * respect to the observation.
00021  *
00022  * A initial observation size may also be specified for efficiency.
00023  * 
00024  * The filter is operated by performing a
00025  * predict, observe
00026  * cycle defined by the base class
00027  */
00028 #include "bayesFlt.hpp"
00029 
00030 /* Filter namespace */
00031 namespace Bayesian_filter
00032 {
00033 
00034 class Covariance_scheme : public Extended_kalman_filter
00035 {
00036 public:
00037     Covariance_scheme (std::size_t x_size, std::size_t z_initialsize = 0);
00038     Covariance_scheme& operator= (const Covariance_scheme&);
00039     // Optimise copy assignment to only copy filter state
00040 
00041     void init ();
00042     void update ();
00043 
00044     Float predict (Linrz_predict_model& f);
00045     // Standard Linrz prediction
00046     Float predict (Gaussian_predict_model& f);
00047     // Specialised 'stationary' prediction, only addative noise
00048 
00049     Float observe_innovation (Linrz_uncorrelated_observe_model& h, const FM::Vec& s);
00050     Float observe_innovation (Linrz_correlated_observe_model& h, const FM::Vec& s);
00051 
00052 public:                     // Exposed Numerical Results
00053     FM::SymMatrix S, SI;        // Innovation Covariance and Inverse
00054     FM::Matrix W;               // Kalman Gain
00055 
00056 protected:                  // Permenantly allocated temps
00057     FM::RowMatrix tempX;
00058 protected:                  // allow fast operation if z_size remains constant
00059     std::size_t last_z_size;
00060     void observe_size (std::size_t z_size);
00061 };
00062 
00063 
00064 }//namespace
00065 #endif

Generated on Wed Oct 4 22:57:23 2006 for Bayes++ Bayesian Filtering Classes by  doxygen 1.4.6