nonminimalkalmanfilter.cpp
Go to the documentation of this file.
1 // $Id$
2 // Copyright (C) 2003 Klaas Gadeyne <first dot last at gmail dot com>
3 // Wim Meeussen <wim dot meeussen at mech dot kuleuven dot ac dot be>
4 //
5 // This program is free software; you can redistribute it and/or modify
6 // it under the terms of the GNU Lesser General Public License as published by
7 // the Free Software Foundation; either version 2.1 of the License, or
8 // (at your option) any later version.
9 //
10 // This program is distributed in the hope that it will be useful,
11 // but WITHOUT ANY WARRANTY; without even the implied warranty of
12 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13 // GNU Lesser General Public License for more details.
14 //
15 // You should have received a copy of the GNU Lesser General Public License
16 // along with this program; if not, write to the Free Software
17 // Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA.
18 //
19 #include "nonminimalkalmanfilter.h"
20 #include "nonminimal_state/linearise.h"
21 #include "../pdf/nonlinearanalyticconditionalgaussian.h"
22 
23 namespace BFL
24 {
25 
26 #define NLinSys NonLinearAnalyticSystemModelGaussianUncertainty
27 #define NLinMeas NonLinearAnalyticMeasurementModelGaussianUncertainty
28 
29 
31  unsigned int NrIterations,
32  vector<NLSysModel*> minimalsysmodels,
33  vector<NLMeasModel*> minimalmeasmodels,
34  vector<GiNaC::symbol> makelinear)
35  : KalmanFilter(prior)
36  {
37  // create linearise
38  Linear = new Linearise(minimalsysmodels, minimalmeasmodels, makelinear);
39 
40  // create STATE
41  MinimalState = Linear->NonlinearStateGet();
42  NonminimalState = Linear->LinearStateGet();
43 
44  // create PRIOR
45  ColumnVector mu_prior(NonminimalState.size()); mu_prior = 0;
46  SymmetricMatrix sigma_prior(NonminimalState.size()); sigma_prior = 0;
47  for (unsigned int i=0; i< NonminimalState.size(); i++)
48  sigma_prior(i+1,i+1) = 333*333;
49  NonminimalPrior = new Gaussian(mu_prior,sigma_prior);
50  MinimalPrior = prior;
51  cout << "nonminimal prior " << *NonminimalPrior << endl;
52 
53  // create FILTER
56 
57 
58  // create MODEL
59  vector<GiNaC::symbol> empty_sym(0);
60  ColumnVector mu_add(NonminimalState.size()); mu_add = 0;
61  Gaussian additiveNoise(mu_add,NonminimalFilter->PostGet().CovarianceGet());
62  NonLinearConditionalGaussian pdf(Linear->SubstitutionGet(), empty_sym, MinimalState, additiveNoise);
63  MinimalMeasModel = new NLinMeas( &pdf );
64 
65  // show substitutions
66  for (unsigned int i=0; i<NonminimalState.size() ; i++)
67  cout << NonminimalState[i] << " -> " << Linear->SubstitutionGet()[i] << endl;
68  }
69 
70 
72  {
73  delete Linear;
74  delete NonminimalPrior;
75  delete NonminimalFilter;
76  delete MinimalFilter;
77  delete MinimalMeasModel;
78  }
79 
80  void
82  const ColumnVector& u)
83  {
84  NonminimalFilter->SysUpdate(Linear->LinearSysModelGet((NLinSys*)sysmodel),u);
85  }
86 
87  void
89  const ColumnVector& z,
90  const ColumnVector& s)
91  {
92  NonminimalFilter->MeasUpdate(Linear->LinearMeasModelGet((NLinMeas*)measmodel),z,s);
93  }
94 
95 }// End namespace
virtual MatrixWrapper::SymmetricMatrix CovarianceGet() const
Get the Covariance Matrix E[(x - E[x])^2] of the Analytic pdf.
Definition: gaussian.cpp:187
virtual ~NonminimalKalmanFilter()
Destructor.
Class representing Gaussian (or normal density)
Definition: gaussian.h:27
IteratedExtendedKalmanFilter * MinimalFilter
virtual void MeasUpdate(MeasurementModel< MatrixWrapper::ColumnVector, MatrixWrapper::ColumnVector > *const measmodel, const MatrixWrapper::ColumnVector &z, const MatrixWrapper::ColumnVector &s)
Measurement Update (overloaded)
IteratedExtendedKalmanFilter * NonminimalFilter
vector< GiNaC::symbol > NonminimalState
virtual void SysUpdate(SystemModel< ColumnVector > *const sysmodel, const ColumnVector &u)
NonminimalKalmanFilter(Gaussian *prior, unsigned int NrIterations, vector< NLSysModel * > minimalsysmodels, vector< NLMeasModel * > minimalmeasmodels, vector< GiNaC::symbol > nonlinearstate=*(new vector< GiNaC::symbol >))
Class representing the family of all Kalman Filters (EKF, IEKF, ...)
Definition: kalmanfilter.h:49
virtual Gaussian * PostGet()
Get Posterior density.
vector< GiNaC::symbol > MinimalState
#define NLinMeas
#define NLinSys
virtual void MeasUpdate(MeasurementModel< ColumnVector, ColumnVector > *const measmodel, const ColumnVector &z, const ColumnVector &s)
virtual void SysUpdate(SystemModel< MatrixWrapper::ColumnVector > *const sysmodel, const MatrixWrapper::ColumnVector &u)
System Update.


bfl
Author(s): Klaas Gadeyne, Wim Meeussen, Tinne Delaet and many others. See web page for a full contributor list. ROS package maintained by Wim Meeussen.
autogenerated on Mon Jun 10 2019 12:47:59