Bayes++ Bayesian Filtering Classes Release 2014.5 - Copyright (c) 2003,2004,2005,2006,2011,2012,2014 Michael Stevens
bayesFlt.hpp
Go to the documentation of this file.
1#ifndef _BAYES_FILTER
2#define _BAYES_FILTER
3
4/*
5 * Bayes++ the Bayesian Filtering Library
6 * Copyright (c) 2002 Michael Stevens
7 * See accompanying Bayes++.htm for terms and conditions of use.
8 *
9 * $Id: bayesFlt.hpp 634 2010-08-15 16:39:44Z mistevens $
10 */
11
12/*
13 * Bayesian filtering represented as Dual hierarchy of:
14 * Prediction and Observation models
15 * Filtering Schemes
16 */
17
18// Common headers required for declarations
19#include "bayesException.hpp" // exception types
20#include "matSupSub.hpp" // matrix support subsystem
21
22/* Filter namespace */
23namespace Bayesian_filter
24{
25 // Allow use of a short name for matrix namespace
26 namespace FM = Bayesian_filter_matrix;
27
28
29/*
30 * Abstraction support classes, at the base of the hierarchy
31 */
32
34/*
35 * A very abstract Polymorphic base representation!
36 * Interface provides: type, internal error handing, and destruction
37 */
38public:
40 // Type used throughout as a number representation for state etc
41
42 virtual ~Bayes_base() = 0;
43 // Polymorphic
44
45 static void error (const Numeric_exception& a);
46 static void error (const Logic_exception& a);
47 // Report a filter, throw a Filter_exception
48 // No exception safety rules are specified, assume the object is invalid
49 // May have side effects for debugging
50};
51
52
54/*
55 * Numerical comparison of reciprocal condition numbers
56 * Required for all linear algebra in models and filters
57 * Implements minimum allowable reciprocal condition number for PD Matrix factorisations
58 */
59{
60public:
62 { limit_PD = limit_PD_init;
63 }
65 { limit_PD = nl;
66 }
67 inline void check_PSD (Bayes_base::Float rcond, const char* error_description) const
68 /* Checks a the reciprocal condition number
69 * Generates a Bayes_filter_exception if value represents a NON PSD matrix
70 * Inverting condition provides a test for IEC 559 NaN values
71 */
72 { if (!(rcond >= 0))
73 Bayes_base::error (Numeric_exception (error_description));
74 }
75
76 inline void check_PD (Bayes_base::Float rcond, const char* error_description) const
77 /* Checks a reciprocal condition number
78 * Generates a Bayes_filter_exception if value represents a NON PD matrix
79 * I.e. rcond is bellow given conditioning limit
80 * Inverting condition provides a test for IEC 559 NaN values
81 */
82 { if (!(rcond >= limit_PD))
83 Bayes_base::error (Numeric_exception (error_description));
84 }
85private:
86 Bayes_base::Float limit_PD;
87 const static Bayes_base::Float limit_PD_init; // Initial common value for limit_PD
88};
89
90
91/*
92 * Abstract Prediction models
93 * Predict models are used to parameterise predict functions of filters
94 */
96{
97 // Empty
98};
99
100
102/* Sampled stochastic predict model
103 x*(k) = fw(x(k-1), w(k))
104 fw should generate samples from the stochastic variable w(k)
105 This fundamental model is used instead of the predict likelihood function L(x*|x)
106 Since drawing samples from an arbitrary L is non-trivial (see MCMC theory)
107 the burden is place on the model to generate these samples.
108 Defines an Interface without data members
109 */
110{
111public:
112 virtual const FM::Vec& fw(const FM::Vec& x) const = 0;
113 // Note: Reference return value as a speed optimisation, MUST be copied by caller.
114};
115
117/* Functional (non-stochastic) predict model f
118 x*(k) = fx(x(k-1))
119 This fundamental model is used instead of the predict likelihood function L(x*|x)
120 Since L is a delta function which isn't much use for numerical systems.
121 Defines an Interface without data members
122 */
123{
124public:
125 virtual const FM::Vec& fx(const FM::Vec& x) const = 0;
126 // Functional model
127 // Note: Reference return value as a speed optimisation, MUST be copied by caller.
128
129 const FM::Vec& operator()(const FM::Vec& x) const
130 { // Operator form of functional model
131 return fx(x);
132 }
133};
134
136/* Gaussian noise predict model
137 This fundamental noise model for linear/linearised filtering
138 x(k|k-1) = x(k-1|k-1)) + G(k)w(k)
139 G(k)w(k)
140 q(k) = state noise covariance, q(k) is covariance of w(k)
141 G(k) = state noise coupling
142*/
143{
144public:
145 Gaussian_predict_model (std::size_t x_size, std::size_t q_size);
146
147 FM::Vec q; // Noise variance (always dense, use coupling to represent sparseness)
148 FM::Matrix G; // Noise Coupling
149
151 // Reciprocal condition number limit of linear components when factorised or inverted
152};
153
155/* Additive Gaussian noise predict model
156 This fundamental model for non-linear filtering with additive noise
157 x(k|k-1) = f(x(k-1|k-1)) + G(k)w(k)
158 q(k) = state noise covariance, q(k) is covariance of w(k)
159 G(k) = state noise coupling
160 ISSUE Should be privately derived from Gaussian_predict_model but access control in GCC is broken
161*/
162{
163public:
164 Additive_predict_model (std::size_t x_size, std::size_t q_size);
165
166 virtual const FM::Vec& f(const FM::Vec& x) const = 0;
167 // Functional part of additive model
168 // Note: Reference return value as a speed optimisation, MUST be copied by caller.
169
170 FM::Vec q; // Noise variance (always dense, use coupling to represent sparseness)
171 FM::Matrix G; // Noise Coupling
172
174 // Reciprocal condition number limit of linear components when factorised or inverted
175};
176
178/* Linrz predict model
179 This fundamental model for linear/linearised filtering
180 x(k|k-1) = f(x(k-1|k-1)
181 Fx(x(k-1|k-1) = Jacobian of of functional part fx with respect to state x
182 */
183{
184public:
185 Linrz_predict_model (std::size_t x_size, std::size_t q_size);
186 FM::Matrix Fx; // Model
187};
188
190/* Linear predict model
191 Enforces linearity on f
192 x(k|k-1) = Fx(k-1|k-1) * x(k-1|k-1)
193 */
194{
195public:
196 Linear_predict_model (std::size_t x_size, std::size_t q_size);
197 const FM::Vec& f(const FM::Vec& x) const
198 { // Provide the linear implementation of functional f
199 xp.assign (FM::prod(Fx,x));
200 return xp;
201 }
202private:
203 mutable FM::Vec xp;
204};
205
207/* Linear invertible predict model
208 Fx has an inverse
209 x(k-1|k-1) = inv.Fx(k-1|k-1) * x(k|k-1)
210 */
211{
212public:
213 Linear_invertible_predict_model (std::size_t x_size, std::size_t q_size);
215 inverse_model (std::size_t x_size);
216 FM::ColMatrix Fx; // Model inverse (ColMatrix as usually transposed)
218};
219
220
221
222/*
223 * Abstract Observation models
224 * Observe models are used to parameterise the observe functions of filters
225 */
227{
228 // Empty
229};
230
232// Function object for predict of observations
233{
234public:
235 virtual const FM::Vec& h(const FM::Vec& x) const = 0;
236 // Note: Reference return value as a speed optimisation, MUST be copied by caller.
237};
238
239
241/* Likelihood observe model L(z |x)
242 * The most fundamental Bayesian definition of an observation
243 * Defines an Interface without data members
244 */
245{
246public:
247 Likelihood_observe_model(std::size_t z_size) : z(z_size)
248 {}
249 virtual Float L(const FM::Vec& x) const = 0;
250 // Likelihood L(z | x)
251
252 virtual void Lz (const FM::Vec& zz)
253 // Set the observation zz about which to evaluate the Likelihood function
254 {
255 z = zz;
256 }
257protected:
258 FM::Vec z; // z set by Lz
259};
260
262/* Functional (non-stochastic) observe model h
263 * zp(k) = hx(x(k|k-1))
264 * This is a separate fundamental model and not derived from likelihood because:
265 * L is a delta function which isn't much use for numerical systems
266 * Defines an Interface without data members
267 */
268{
269public:
270 Functional_observe_model(std::size_t /*z_size*/)
271 {}
272 const FM::Vec& operator()(const FM::Vec& x) const
273 { return h(x);
274 }
275
276};
277
279/* Observation model parametised with a fixed z size
280 * Includes the functional part of a noise model
281 * Model is assume to have linear and non-linear components
282 * Linear components need to be checked for conditioning
283 * Non-linear components may be discontinuous and need normalisation
284 */
285{
286public:
287 Parametised_observe_model(std::size_t /*z_size*/)
288 {}
289 virtual const FM::Vec& h(const FM::Vec& x) const = 0;
290 // Functional part of additive model
291 virtual void normalise (FM::Vec& /*z_denorm*/, const FM::Vec& /*z_from*/) const
292 // Discontinuous h. Normalise one observation (z_denorm) from another
293 {} // Default normalisation, z_denorm unchanged
294
296 // Reciprocal condition number limit of linear components when factorised or inverted
297};
298
300/* Observation model, uncorrelated additive observation noise
301 Z(k) = I * Zv(k) observe noise variance vector Zv
302 */
303{
304public:
306 Parametised_observe_model(z_size), Zv(z_size)
307 {}
308 FM::Vec Zv; // Noise Variance
309};
310
312/* Observation model, correlated additive observation noise
313 Z(k) = observe noise covariance
314 */
315{
316public:
318 Parametised_observe_model(z_size), Z(z_size,z_size)
319 {}
320 FM::SymMatrix Z; // Noise Covariance (not necessarily dense)
321};
322
324/* Linrz observation model Hx, h about state x (fixed size)
325 Hx(x(k|k-1) = Jacobian of h with respect to state x
326 Normalisation consistency Hx: Assume normalise will be from h(x(k|k-1)) so result is consistent with Hx
327 */
328{
329public:
330 FM::Matrix Hx; // Model
331protected: // Jacobian model is not sufficient, it is used to build Linrz observe model's
332 Jacobian_observe_model (std::size_t x_size, std::size_t z_size) :
333 Hx(z_size, x_size)
334 {}
335};
336
338/* Linrz observation model Hx, h with respect to state x (fixed size)
339 correlated observation noise
340 zp(k) = h(x(k-1|k-1)
341 Hx(x(k|k-1) = Jacobian of f with respect to state x
342 Z(k) = observe noise covariance
343 */
344{
345public:
346 Linrz_correlated_observe_model (std::size_t x_size, std::size_t z_size) :
348 {}
349};
350
352/* Linrz observation model Hx, h with respect to state x (fixed size)
353 uncorrelated observation noise
354 zp(k) = h(x(k-1|k-1)
355 Hx(x(k|k-1) = Jacobian of f with respect to state x
356 Zv(k) = observe noise covariance
357 */
358{
359public:
360 Linrz_uncorrelated_observe_model (std::size_t x_size, std::size_t z_size) :
362 {}
363};
364
366/* Linear observation model, correlated observation noise
367 zp(k) = Hx(k) * x(k|k-1)
368 Enforces linear model invariant. Careful when deriving to to change this invariant!
369 */
370{
371public:
372 Linear_correlated_observe_model (std::size_t x_size, std::size_t z_size) :
373 Linrz_correlated_observe_model(x_size, z_size), hx(z_size)
374 {}
375 const FM::Vec& h(const FM::Vec& x) const
376 { // Provide a linear implementation of functional h assumes model is already Linrz for Hx
377 hx.assign (FM::prod(Hx,x));
378 return hx;
379 }
380private:
381 mutable FM::Vec hx;
382};
383
385/* Linear observation model, uncorrelated observation noise
386 zp(k) = Hx(k) * x(k|k-1)
387 Enforces linear model invariant. Careful when deriving to to change this invariant!
388 */
389{
390public:
391 Linear_uncorrelated_observe_model (std::size_t x_size, std::size_t z_size) :
392 Linrz_uncorrelated_observe_model(x_size, z_size), hx(z_size)
393 {}
394 const FM::Vec& h(const FM::Vec& x) const
395 { // Provide a linear implementation of functional h assumes model is already Linrz for Hx
396 hx.assign (FM::prod(Hx,x));
397 return hx;
398 }
399private:
400 mutable FM::Vec hx;
401};
402
403
404/*
405 * Bayesian Filter
406 *
407 * A Bayesian Filter uses Bayes rule to fuse the state probabilities
408 * of a prior and a likelihood function
409 */
411{
412 // Empty
413};
414
415/*
416 * Likelihood Filter - Abstract filtering property
417 * Represents only the Bayesian Likelihood of a state observation
418 */
420{
421public:
422 /* Virtual functions for filter algorithm */
423
424 virtual void observe (Likelihood_observe_model& h, const FM::Vec& z) = 0;
425 /* Observation state posterior using likelihood model h at z
426 */
427};
428
429/*
430 * Functional Filter - Abstract filtering property
431 * Represents only filter predict by a simple functional
432 * (non-stochastic) model
433 *
434 * A similar functional observe is not generally useful. The inverse of h is needed for observe!
435 */
437{
438public:
439 /* Virtual functions for filter algorithm */
440
441 virtual void predict (Functional_predict_model& f) = 0;
442 /* Predict state with functional no noise model
443 Requires x(k|k), X(k|k) or internal equivalent
444 Predicts x(k+1|k), X(k+1|k), using predict model
445 */
446};
447
448/*
449 * State Filter - Abstract filtering property
450 * Represents only filter state and an update on that state
451 */
452class State_filter : virtual public Bayes_filter_base
453{
454public:
455 State_filter (std::size_t x_size);
456 /* Set constant sizes, state must not be empty (must be >=1)
457 Exceptions:
458 bayes_filter_exception is x_size < 1
459 */
460
461 FM::Vec x; // expected state
462
463 /* Virtual functions for filter algorithm */
464
465 virtual void update () = 0;
466 /* Update filters state
467 Updates x(k|k)
468 */
469};
470
471
472/*
473 * Kalman State Filter - Abstract filtering property
474 * Linear filter representation for 1st (mean) and 2nd (covariance) moments of a distribution
475 *
476 * Probability distributions are represented by state vector (x) and a covariance matrix.(X)
477 *
478 * State (x) sizes is assumed to remain constant.
479 * The state and state covariance are public so they can be directly manipulated.
480 * init: Should be called if x or X are altered
481 * update: Guarantees that any internal changes made filter are reflected in x,X.
482 * This allows considerable flexibility so filter implementations can use different numerical representations
483 *
484 * Derived filters supply definitions for the abstract functions and determine the algorithm used
485 * to implement the filter.
486 */
487
489{
490public:
491 FM::SymMatrix X; // state covariance
492
493 Kalman_state_filter (std::size_t x_size);
494 /* Initialise filter and set constant sizes
495 */
496
497 /* Virtual functions for filter algorithm */
498
499 virtual void init () = 0;
500 /* Initialise from current state and state covariance
501 Requires x(k|k), X(k|k)
502 */
503 void init_kalman (const FM::Vec& x, const FM::SymMatrix& X);
504 /* Initialise from a state and state covariance
505 Parameters that reference the instance's x and X members are valid
506 */
507 virtual void update () = 0;
508 /* Update filters state and state covariance
509 Updates x(k|k), X(k|k)
510 */
511
512 // Minimum allowable reciprocal condition number for PD Matrix factorisations
514};
515
516
517/*
518 * Information State Filter - Abstract filtering property
519 * Linear filter information space representation for 1st (mean) and 2nd (covariance) moments of a distribution
520 * Y = inv(X) Information
521 * y = Y*x Information state
522 */
523
525{
526public:
527 Information_state_filter (std::size_t x_size);
528 FM::Vec y; // Information state
529 FM::SymMatrix Y; // Information
530
531 virtual void init_yY () = 0;
532 /* Initialise from a information state and information
533 Requires y(k|k), Y(k|k)
534 Parameters that reference the instance's y and Y members are valid
535 */
536 void init_information (const FM::Vec& y, const FM::SymMatrix& Y);
537 /* Initialise from a information state and information
538 Parameters that reference the instance's y and Y members are valid
539 */
540
541 virtual void update_yY () = 0;
542 /* Update filters information state and information
543 Updates y(k|k), Y(k|k)
544 */
545};
546
547
548/*
549 * Linearizable filter models - Abstract filtering property
550 * Linrz == A linear, or gradient Linearized filter
551 *
552 * Predict uses a Linrz_predict_model that maintains a Jacobian matrix Fx and additive noise
553 * NOTE: Functional (non-stochastic) predict is NOT possible as predict requires Fx.
554 *
555 * Observe uses a Linrz_observe_model and a variable size observation (z)
556 * There are two variants for correlated and uncorrelated observation noise
557 * Derived filters supply the init,predict,observe,update functions and determine
558 * the algorithm used to implement the filter.
559 */
560
561class Linrz_filter : virtual public Bayes_filter_base
562{
563public:
564 /* Virtual functions for filter algorithm */
565
567 /* Predict state using a Linrz model
568 Requires x(k|k), X(k|k) or internal equivilent
569 Returns: Reciprocal condition number of primary matrix used in predict computation (1. if none)
570 */
571
574 /* Observation z(k) and with (Un)correlated observation noise model
575 Requires x(k|k), X(k|k) or internal equivalent
576 Returns: Reciprocal condition number of primary matrix used in observe computation (1. if none)
577 */
578};
579
580
581/*
582 * Linearizable Kalman Filter
583 * Kalman state representation and linearizable models
584 *
585 * Common abstraction for many linear filters
586 * Has a virtual base to represent the common state
587 */
589{
590protected:
591 Linrz_kalman_filter() : Kalman_state_filter(0) // define a default constructor
592 {}
593};
594
595
596/*
597 * Extended Kalman Filter
598 * Kalman state representation and linearizable models
599 *
600 * Observe is implemented using an innovation computed from the non-linear part of the
601 * observe model and linear part of the Linrz_observe_model
602 *
603 * Common abstraction for many linear filters
604 * Has a virtual base to represent the common state
605 */
607{
608protected:
609 Extended_kalman_filter() : Kalman_state_filter(0) // define a default constructor
610 {}
611public:
614 /* Observation z(k) and with (Un)correlated observation noise model
615 Requires x(k|k), X(k|k) or internal equivalent
616 Returns: Reciprocal condition number of primary matrix used in observe computation (1. if none)
617 Default implementation simple computes innovation for observe_innovation
618 */
619
622 /* Observation innovation s(k) and with (Un)correlated observation noise model
623 Requires x(k|k), X(k|k) or internal equivalent
624 Returns: Reciprocal condition number of primary matrix used in observe computation (1. if none)
625 */
626};
627
628
629/*
630 * Sample State Filter - Abstract filtering property
631 *
632 * Probability distributions are represented by a finite sampling
633 *
634 * State (x_size) size and its sampling (s_size) are assumed to remain constant.
635 * The state sampling public so they can be directly manipulated.
636 * init: Should be used if they to be altered
637 * update: Guarantees that any internal changes made filter are reflected in sampling S.
638 */
639
641{
642public:
643 FM::ColMatrix S; // state sampling (x_size,s_size)
644
645 Sample_state_filter (std::size_t x_size, std::size_t s_size);
646 /* Initialise filter and set constant sizes for
647 x_size of the state vector
648 s_size sample size
649 Exceptions:
650 bayes_filter_exception is s_size < 1
651 */
653
654 /* Virtual functions for filter algorithm */
655
656 virtual void init_S () = 0;
657 /* Initialise from current sampling
658 */
659
660 void init_sample (const FM::ColMatrix& initS);
661 /* Initialise from a sampling
662 */
663
664 virtual Float update_resample () = 0;
665 /* Resampling update
666 Returns lcond, Smallest normalised likelihood weight, represents conditioning of resampling solution
667 lcond == 1. if no resampling performed
668 This should by multiplied by the number of samples to get the Likelihood function conditioning
669 */
670
671 std::size_t unique_samples () const;
672 /* Count number of unique (unequal value) samples in S
673 Implementation requires std::sort on sample column references
674 */
675};
676
677
678/*
679 * Sample Filter: Bayes filter using
680 *
681 * Probability distributions are represented by a finite sampling
682 *
683 * The filter is operated by performing a
684 * predict, observe
685 * cycle derived from the bayes_filter. observe Likelihoods are merged into a single combined weight.
686 * update: MUST be used to complete a explicit resampling of the particles using merged weights
687 *
688 * Derived filters supply definitions for the abstract functions and determine the algorithm used
689 * to implement the filter.
690 */
691
693{
694public:
695 Sample_filter (std::size_t x_size, std::size_t s_size);
696 /* Initialise filter and set constant sizes for
697 x_size of the state vector
698 s_size sample size
699 Exceptions:
700 bayes_filter_exception is s_size < 1
701 */
702
703 /* Virtual functions for filter algorithm */
704
705 virtual void predict (Functional_predict_model& f);
706 /* Predict state posterior with functional no noise model
707 */
708
709 virtual void predict (Sampled_predict_model& f) = 0;
710 /* Predict state posterior with sampled noise model
711 */
712
713 virtual void observe (Likelihood_observe_model& h, const FM::Vec& z) = 0;
714 /* Observation state posterior using likelihood model h at z
715 */
716
717 virtual void observe_likelihood (const FM::Vec& lw) = 0;
718 /* Observation fusion directly from likelihood weights
719 lw may be smaller then the state sampling. Weights for additional particles are assumed to be 1
720 */
721};
722
723
724}//namespace
725#endif
Definition bayesFlt.hpp:162
Numerical_rcond rclimit
Definition bayesFlt.hpp:173
FM::Vec q
Definition bayesFlt.hpp:170
FM::Matrix G
Definition bayesFlt.hpp:171
virtual const FM::Vec & f(const FM::Vec &x) const =0
Definition bayesFlt.hpp:33
virtual ~Bayes_base()=0
Definition bayesFlt.cpp:30
static void error(const Numeric_exception &a)
Definition bayesFlt.cpp:35
Bayesian_filter_matrix::Float Float
Definition bayesFlt.hpp:39
Definition bayesFlt.hpp:411
FM::SymMatrix Z
Definition bayesFlt.hpp:320
Correlated_additive_observe_model(std::size_t z_size)
Definition bayesFlt.hpp:317
Definition bayesFlt.hpp:607
virtual Float observe_innovation(Linrz_uncorrelated_observe_model &h, const FM::Vec &s)=0
virtual Float observe(Linrz_uncorrelated_observe_model &h, const FM::Vec &z)
Definition bayesFlt.cpp:131
Extended_kalman_filter()
Definition bayesFlt.hpp:609
virtual Float observe_innovation(Linrz_correlated_observe_model &h, const FM::Vec &s)=0
Definition bayesFlt.hpp:437
virtual void predict(Functional_predict_model &f)=0
const FM::Vec & operator()(const FM::Vec &x) const
Definition bayesFlt.hpp:272
Functional_observe_model(std::size_t)
Definition bayesFlt.hpp:270
const FM::Vec & operator()(const FM::Vec &x) const
Definition bayesFlt.hpp:129
virtual const FM::Vec & fx(const FM::Vec &x) const =0
Definition bayesFlt.hpp:143
Numerical_rcond rclimit
Definition bayesFlt.hpp:150
FM::Vec q
Definition bayesFlt.hpp:147
FM::Matrix G
Definition bayesFlt.hpp:148
void init_information(const FM::Vec &y, const FM::SymMatrix &Y)
Definition bayesFlt.cpp:151
FM::SymMatrix Y
Definition bayesFlt.hpp:529
FM::Vec y
Definition bayesFlt.hpp:528
Definition bayesFlt.hpp:328
Jacobian_observe_model(std::size_t x_size, std::size_t z_size)
Definition bayesFlt.hpp:332
FM::Matrix Hx
Definition bayesFlt.hpp:330
Definition bayesFlt.hpp:489
void init_kalman(const FM::Vec &x, const FM::SymMatrix &X)
Definition bayesFlt.cpp:105
FM::SymMatrix X
Definition bayesFlt.hpp:491
Numerical_rcond rclimit
Definition bayesFlt.hpp:513
Definition bayesFlt.hpp:420
virtual void observe(Likelihood_observe_model &h, const FM::Vec &z)=0
virtual void Lz(const FM::Vec &zz)
Definition bayesFlt.hpp:252
FM::Vec z
Definition bayesFlt.hpp:258
virtual Float L(const FM::Vec &x) const =0
Likelihood_observe_model(std::size_t z_size)
Definition bayesFlt.hpp:247
const FM::Vec & h(const FM::Vec &x) const
Definition bayesFlt.hpp:375
Linear_correlated_observe_model(std::size_t x_size, std::size_t z_size)
Definition bayesFlt.hpp:372
struct Bayesian_filter::Linear_invertible_predict_model::inverse_model inv
Definition bayesFlt.hpp:194
const FM::Vec & f(const FM::Vec &x) const
Definition bayesFlt.hpp:197
Linear_uncorrelated_observe_model(std::size_t x_size, std::size_t z_size)
Definition bayesFlt.hpp:391
const FM::Vec & h(const FM::Vec &x) const
Definition bayesFlt.hpp:394
Linrz_correlated_observe_model(std::size_t x_size, std::size_t z_size)
Definition bayesFlt.hpp:346
Definition bayesFlt.hpp:562
virtual Float observe(Linrz_correlated_observe_model &h, const FM::Vec &z)=0
virtual Float observe(Linrz_uncorrelated_observe_model &h, const FM::Vec &z)=0
virtual Float predict(Linrz_predict_model &f)=0
Definition bayesFlt.hpp:589
Linrz_kalman_filter()
Definition bayesFlt.hpp:591
Definition bayesFlt.hpp:183
FM::Matrix Fx
Definition bayesFlt.hpp:186
Linrz_uncorrelated_observe_model(std::size_t x_size, std::size_t z_size)
Definition bayesFlt.hpp:360
Definition bayesException.hpp:45
Definition bayesException.hpp:56
Definition bayesFlt.hpp:59
void set_limit_PD(Bayes_base::Float nl)
Definition bayesFlt.hpp:64
void check_PD(Bayes_base::Float rcond, const char *error_description) const
Definition bayesFlt.hpp:76
Numerical_rcond()
Definition bayesFlt.hpp:61
void check_PSD(Bayes_base::Float rcond, const char *error_description) const
Definition bayesFlt.hpp:67
Definition bayesFlt.hpp:233
virtual const FM::Vec & h(const FM::Vec &x) const =0
Definition bayesFlt.hpp:227
virtual void normalise(FM::Vec &, const FM::Vec &) const
Definition bayesFlt.hpp:291
virtual const FM::Vec & h(const FM::Vec &x) const =0
Numerical_rcond rclimit
Definition bayesFlt.hpp:295
Parametised_observe_model(std::size_t)
Definition bayesFlt.hpp:287
Definition bayesFlt.hpp:96
Definition bayesFlt.hpp:693
virtual void predict(Functional_predict_model &f)
Definition bayesFlt.cpp:257
virtual void observe_likelihood(const FM::Vec &lw)=0
virtual void observe(Likelihood_observe_model &h, const FM::Vec &z)=0
virtual void predict(Sampled_predict_model &f)=0
Definition bayesFlt.hpp:641
~Sample_state_filter()=0
Definition bayesFlt.cpp:172
void init_sample(const FM::ColMatrix &initS)
Definition bayesFlt.cpp:179
FM::ColMatrix S
Definition bayesFlt.hpp:643
std::size_t unique_samples() const
Definition bayesFlt.cpp:218
Definition bayesFlt.hpp:110
virtual const FM::Vec & fw(const FM::Vec &x) const =0
Definition bayesFlt.hpp:453
FM::Vec x
Definition bayesFlt.hpp:461
Uncorrelated_additive_observe_model(std::size_t z_size)
Definition bayesFlt.hpp:305
Definition matSup.cpp:34
FMMatrix< detail::BaseColMatrix > ColMatrix
Definition uBLASmatrix.hpp:326
FMMatrix< detail::SymMatrixWrapper< detail::BaseRowMatrix > > SymMatrix
Definition uBLASmatrix.hpp:327
FMVec< detail::BaseVector > Vec
Definition uBLASmatrix.hpp:323
RowMatrix Matrix
Definition uBLASmatrix.hpp:325
double Float
Definition matSupSub.hpp:55
Definition bayesException.hpp:21