complete_filter_test.cpp
Go to the documentation of this file.
1 // Copyright (C) 2007 Wim Meeussen <wim DOT meeussen AT mech DOT kuleuven DOT be>
2 // Copyright (C) 2008 Tinne De Laet <tinne DOT delaet AT mech DOT kuleuven DOT be>
3 //
4 // This program is free software; you can redistribute it and/or modify
5 // it under the terms of the GNU General Public License as published by
6 // the Free Software Foundation; either version 2 of the License, or
7 // (at your option) any later version.
8 //
9 // This program is distributed in the hope that it will be useful,
10 // but WITHOUT ANY WARRANTY; without even the implied warranty of
11 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 // GNU General Public License for more details.
13 //
14 // You should have received a copy of the GNU General Public License
15 // along with this program; if not, write to the Free Software
16 // Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA.
17 //
18 
19 
20 #include "complete_filter_test.hpp"
21 #include "approxEqual.hpp"
22 
23 
24 
25 
26 // Registers the fixture into the 'registry'
28 
29 using namespace MatrixWrapper;
30 using namespace BFL;
31 
32 
33 void
35 {
36 }
37 
38 
39 void
41 {
42 }
43 
44 void
46 {
47  double epsilon = 0.015;
48  double epsilon_large = 0.5;
49  double epsilon_huge = 2.0;
50 
51  /****************************
52  * Initialise system model *
53  ***************************/
54  ColumnVector SysNoise_Mu(STATE_SIZE);
55  SysNoise_Mu = 0.0;
56  SysNoise_Mu(1) = MU_SYSTEM_NOISE_X;
57  SysNoise_Mu(2) = MU_SYSTEM_NOISE_Y;
58  SysNoise_Mu(3) = MU_SYSTEM_NOISE_THETA;
59 
60  SymmetricMatrix SysNoise_Cov(STATE_SIZE);
61  SysNoise_Cov = 0.0;
62  // Uncertainty or Noice (Additive) and Matrix A
63  SysNoise_Cov(1,1) = SIGMA_SYSTEM_NOISE_X;
64  SysNoise_Cov(2,2) = SIGMA_SYSTEM_NOISE_Y;
65  SysNoise_Cov(3,3) = SIGMA_SYSTEM_NOISE_THETA;
66 
67  Gaussian System_Uncertainty(SysNoise_Mu, SysNoise_Cov);
68  NonLinearAnalyticConditionalGaussianMobile sys_pdf(System_Uncertainty);
69  AnalyticSystemModelGaussianUncertainty sys_model(&sys_pdf);
70 
71 
72  /*********************************
73  * Initialise measurement model *
74  ********************************/
75  // Fill up H
76  double wall_ct = 2/(sqrt(pow(RICO_WALL,2.0) + 1));
77  Matrix H(MEAS_SIZE,STATE_SIZE);
78  H = 0.0;
79  H(1,1) = wall_ct * RICO_WALL;
80  H(1,2) = 0 - wall_ct;
81 
82  // Construct the measurement noise (a scalar in this case)
83  ColumnVector MeasNoise_Mu(MEAS_SIZE);
84  SymmetricMatrix MeasNoise_Cov(MEAS_SIZE);
85  MeasNoise_Mu(1) = MU_MEAS_NOISE;
86  MeasNoise_Cov(1,1) = SIGMA_MEAS_NOISE;
87 
88  Gaussian Measurement_Uncertainty(MeasNoise_Mu,MeasNoise_Cov);
89  LinearAnalyticConditionalGaussian meas_pdf(H,Measurement_Uncertainty);
91 
92  /****************************
93  * Initialise prior DENSITY *
94  ***************************/
95  // Continuous Gaussian prior (for Kalman filters)
96  ColumnVector prior_mu(STATE_SIZE);
97  SymmetricMatrix prior_sigma(STATE_SIZE);
98  prior_mu(1) = PRIOR_MU_X;
99  prior_mu(2) = PRIOR_MU_Y;
100  prior_mu(STATE_SIZE) = PRIOR_MU_THETA;
101  prior_sigma = 0.0;
102  prior_sigma(1,1) = PRIOR_COV_X;
103  prior_sigma(2,2) = PRIOR_COV_Y;
104  prior_sigma(3,3) = PRIOR_COV_THETA;
105  Gaussian prior_cont(prior_mu,prior_sigma);
106 
107  // Discrete prior for Particle filter (using the continuous Gaussian prior)
108  vector<Sample<ColumnVector> > prior_samples(NUM_SAMPLES);
110  prior_cont.SampleFrom(prior_samples,NUM_SAMPLES,CHOLESKY,NULL);
111  prior_discr.ListOfSamplesSet(prior_samples);
112 
113  // Mixture prior for the Mixture Boostrap filter
114  ColumnVector prior_mu1(STATE_SIZE);
115  SymmetricMatrix prior_sigma1(STATE_SIZE);
116  prior_mu1(1) = PRIOR_MU_X1;
117  prior_mu1(2) = PRIOR_MU_Y1;
118  prior_mu1(STATE_SIZE) = PRIOR_MU_THETA1;
119  prior_sigma1 = 0.0;
120  prior_sigma1(1,1) = PRIOR_COV_X1;
121  prior_sigma1(2,2) = PRIOR_COV_Y1;
122  prior_sigma1(3,3) = PRIOR_COV_THETA1;
123  Gaussian prior_cont1(prior_mu1,prior_sigma1);
124 
126  prior_cont1.SampleFrom(prior_samples,NUM_SAMPLES,CHOLESKY,NULL);
127  mixcomp1.ListOfSamplesSet(prior_samples);
128 
129  ColumnVector prior_mu2(STATE_SIZE);
130  SymmetricMatrix prior_sigma2(STATE_SIZE);
131  prior_mu2(1) = PRIOR_MU_X2;
132  prior_mu2(2) = PRIOR_MU_Y2;
133  prior_mu2(STATE_SIZE) = PRIOR_MU_THETA2;
134  prior_sigma2 = 0.0;
135  prior_sigma2(1,1) = PRIOR_COV_X2;
136  prior_sigma2(2,2) = PRIOR_COV_Y2;
137  prior_sigma2(3,3) = PRIOR_COV_THETA2;
138  Gaussian prior_cont2(prior_mu2,prior_sigma2);
139 
141  prior_cont2.SampleFrom(prior_samples,NUM_SAMPLES,CHOLESKY,NULL);
142  mixcomp2.ListOfSamplesSet(prior_samples);
143 
144  ColumnVector prior_mu3(STATE_SIZE);
145  SymmetricMatrix prior_sigma3(STATE_SIZE);
146  prior_mu3(1) = PRIOR_MU_X3;
147  prior_mu3(2) = PRIOR_MU_Y3;
148  prior_mu3(STATE_SIZE) = PRIOR_MU_THETA3;
149  prior_sigma3 = 0.0;
150  prior_sigma3(1,1) = PRIOR_COV_X3;
151  prior_sigma3(2,2) = PRIOR_COV_Y3;
152  prior_sigma3(3,3) = PRIOR_COV_THETA3;
153  Gaussian prior_cont3(prior_mu3,prior_sigma3);
154 
156  prior_cont3.SampleFrom(prior_samples,NUM_SAMPLES,CHOLESKY,NULL);
157  mixcomp3.ListOfSamplesSet(prior_samples);
158 
159  ColumnVector prior_mu4(STATE_SIZE);
160  SymmetricMatrix prior_sigma4(STATE_SIZE);
161  prior_mu4(1) = PRIOR_MU_X4;
162  prior_mu4(2) = PRIOR_MU_Y4;
163  prior_mu4(STATE_SIZE) = PRIOR_MU_THETA3;
164  prior_sigma4 = 0.0;
165  prior_sigma4(1,1) = PRIOR_COV_X4;
166  prior_sigma4(2,2) = PRIOR_COV_Y4;
167  prior_sigma4(3,3) = PRIOR_COV_THETA4;
168  Gaussian prior_cont4(prior_mu4,prior_sigma4);
169 
171  prior_cont4.SampleFrom(prior_samples,NUM_SAMPLES,CHOLESKY,NULL);
172  mixcomp4.ListOfSamplesSet(prior_samples);
173 
174  vector<Pdf<ColumnVector>*> mixVec(3);
175  mixVec[0] = &mixcomp1;
176  mixVec[1] = &mixcomp2;
177  mixVec[2] = &mixcomp3;
178  //mixVec[3] = &mixcomp4;
179  Mixture<ColumnVector> prior_mix(mixVec);
180 
181  // check
182  ColumnVector mean_check(STATE_SIZE);
183  mean_check(1) = PRIOR_MU_X; mean_check(2) = PRIOR_MU_Y; mean_check(3) = PRIOR_MU_THETA;
184  SymmetricMatrix cov_check(STATE_SIZE);
185  cov_check(1,1) = PRIOR_COV_X; cov_check(1,2) = 0; cov_check(1,3) = 0;
186  cov_check(2,1) = 0; cov_check(2,2) = PRIOR_COV_Y; cov_check(2,3) = 0;
187  cov_check(3,1) = 0; cov_check(3,2) = 0; cov_check(3,3) = PRIOR_COV_THETA;
188  CPPUNIT_ASSERT_EQUAL(approxEqual(prior_cont.ExpectedValueGet(), mean_check, epsilon),true);
189  CPPUNIT_ASSERT_EQUAL(approxEqual(prior_cont.CovarianceGet(), cov_check, epsilon),true);
190 
191 
192  /***************************
193  * initialise MOBILE ROBOT *
194  **************************/
195  // Model of mobile robot in world
196  // The model is used to simultate the distance measurements.
197  MobileRobot mobile_robot;
198  ColumnVector input(INPUT_SIZE);
199  input(1) = LIN_SPEED * DELTA_T;
200  input(2) = ROT_SPEED * DELTA_T;
201 
202 
203  /******************************
204  * Construction of the Filter *
205  ******************************/
206  Filter<ColumnVector,ColumnVector> *my_filter_extendedkalman, *my_filter_iteratedextendedkalman, *my_filter_bootstrap, *my_filter_ekparticle, *my_filter_mixtureBootstrap;
207  my_filter_extendedkalman = new ExtendedKalmanFilter(&prior_cont);
208  my_filter_iteratedextendedkalman = new IteratedExtendedKalmanFilter(&prior_cont,NUM_ITERATIONS);
209  my_filter_bootstrap = new BootstrapFilter<ColumnVector,ColumnVector> (&prior_discr, RESAMPLE_PERIOD, RESAMPLE_THRESHOLD);
210  my_filter_ekparticle = new EKParticleFilter(&prior_discr, 0, RESAMPLE_THRESHOLD);
211  my_filter_mixtureBootstrap = new MixtureBootstrapFilter<ColumnVector,ColumnVector> (&prior_mix, RESAMPLE_PERIOD, RESAMPLE_THRESHOLD);
212 
213  /*******************
214  * ESTIMATION LOOP *
215  *******************/
216  ColumnVector measurement ;
217  ColumnVector mobile_robot_state ;
218  Pdf<ColumnVector> * posterior_mixtureBootstrap;
219  ofstream mixtureFile;
220  if(OUTPUT_MIXTURE)
221  {
222  mixtureFile.open("mixtureOutput.txt");
223  }
224 
225  cout << "Running 4 different filters. This may take a few minutes... " << endl;
226  unsigned int time_step;
227  for (time_step = 0; time_step < NUM_TIME_STEPS-1; time_step++)
228  {
229  // DO ONE STEP WITH MOBILE ROBOT
230  mobile_robot.Move(input);
231 
232  // DO ONE MEASUREMENT
233  measurement = mobile_robot.Measure();
234  mobile_robot_state = mobile_robot.GetState();
235 
236  if(OUTPUT_MIXTURE)
237  {
238  posterior_mixtureBootstrap = my_filter_mixtureBootstrap->PostGet();
239  vector<WeightedSample<ColumnVector> > los;
240  vector<WeightedSample<ColumnVector> >::iterator los_it;
241  int numComp = dynamic_cast<Mixture<ColumnVector> *>(posterior_mixtureBootstrap)->NumComponentsGet();
242  mixtureFile << time_step << " " << numComp << " ";
243  mixtureFile << mobile_robot_state(1) << " " << mobile_robot_state(2) << " " << mobile_robot_state(3) << " ";
244  for(int i = 0 ; i<numComp ; i++ )
245  {
246  double componentWeight = ( dynamic_cast<Mixture<ColumnVector> *>(posterior_mixtureBootstrap)->WeightGet(i)) ;
247  los = dynamic_cast<MCPdf<ColumnVector> *>( dynamic_cast<Mixture<ColumnVector> *>(posterior_mixtureBootstrap)->ComponentGet(i))->ListOfSamplesGet();
248  mixtureFile << i << " " << componentWeight << " " << los.size()<< " " << STATE_SIZE << " ";
249  for ( los_it=los.begin(); los_it != los.end() ; los_it++)
250  {
251  for (int j=0; j<STATE_SIZE ; j++)
252  mixtureFile << los_it->ValueGet()[j] << " ";
253  mixtureFile<< los_it->WeightGet() << " ";
254  }
255  }
256  mixtureFile<<endl;
257  }
258  // UPDATE FILTER
259  my_filter_extendedkalman->Update(&sys_model,input,&meas_model, measurement);
260  my_filter_iteratedextendedkalman->Update(&sys_model,input,&meas_model, measurement);
261  my_filter_bootstrap->Update(&sys_model,input,&meas_model, measurement);
262  //my_filter_ekparticle->Update(&sys_model,input,&meas_model, measurement);
263  my_filter_mixtureBootstrap->Update(&sys_model,input,&meas_model, measurement);
264  }
265 
266  if(OUTPUT_MIXTURE)
267  {
268  posterior_mixtureBootstrap = my_filter_mixtureBootstrap->PostGet();
269  vector<WeightedSample<ColumnVector> > los;
270  vector<WeightedSample<ColumnVector> >::iterator los_it;
271  int numComp = dynamic_cast<Mixture<ColumnVector> *>(posterior_mixtureBootstrap)->NumComponentsGet();
272  mixtureFile << time_step << " " << numComp << " ";
273  mixtureFile << mobile_robot_state(1) << " " << mobile_robot_state(2) << " " << mobile_robot_state(3) << " ";
274  for(int i = 0 ; i<numComp ; i++ )
275  {
276  double componentWeight = ( dynamic_cast<Mixture<ColumnVector> *>(posterior_mixtureBootstrap)->WeightGet(i)) ;
277  los = dynamic_cast<MCPdf<ColumnVector> *>( dynamic_cast<Mixture<ColumnVector> *>(posterior_mixtureBootstrap)->ComponentGet(i))->ListOfSamplesGet();
278  mixtureFile << i << " " << componentWeight << " " << los.size()<< " " << STATE_SIZE << " ";
279  for ( los_it=los.begin(); los_it != los.end() ; los_it++)
280  {
281  for (int j=0; j<STATE_SIZE ; j++)
282  mixtureFile << los_it->ValueGet()[j] << " ";
283  mixtureFile<< los_it->WeightGet() << " ";
284  }
285  }
286  mixtureFile<<endl;
287  }
288 
289 
290  // ek_check
291  Pdf<ColumnVector> * posterior_extendedkalman = my_filter_extendedkalman->PostGet();
292  ColumnVector mean_ek_check(STATE_SIZE);
293  mean_ek_check=mobile_robot.GetState();
294  //mean_ek_check(1) = mobile_robot_state(1); mean_ek_check(2) = mobile_robot_state(2); mean_ek_check(3) = mobile_robot_state(3);
295  SymmetricMatrix cov_ek_check(STATE_SIZE);
296  cov_ek_check(1,1) = 0.0599729; cov_ek_check(1,2) = 0.000291386; cov_ek_check(1,3) = 0.00223255;
297  cov_ek_check(2,1) = 0.000291386; cov_ek_check(2,2) = 0.000277528; cov_ek_check(2,3) = 0.000644136;
298  cov_ek_check(3,1) = 0.00223255; cov_ek_check(3,2) = 0.000644136; cov_ek_check(3,3) = 0.00766009;
299  CPPUNIT_ASSERT_EQUAL(approxEqual(posterior_extendedkalman->ExpectedValueGet(), mean_ek_check, epsilon_large),true);
300  CPPUNIT_ASSERT_EQUAL(approxEqual(posterior_extendedkalman->CovarianceGet(), cov_ek_check, epsilon),true);
301 
302  // it_check
303  Pdf<ColumnVector> * posterior_iteratedextendedkalman = my_filter_iteratedextendedkalman->PostGet();
304  ColumnVector mean_it_check(STATE_SIZE);
305  mean_it_check=mobile_robot.GetState();
306  //mean_it_check(1) = mobile_robot_state(1); mean_it_check(2) = mobile_robot_state(2); mean_it_check(3) = mobile_robot_state(3);
307  SymmetricMatrix cov_it_check(STATE_SIZE);
308  cov_it_check = 0.0;
309  cov_it_check(1,1) = 0.0611143; cov_it_check(1,2) = 0.000315923; cov_it_check(1,3) = 0.00238938;
310  cov_it_check(2,1) = 0.000315923; cov_it_check(2,2) = 0.000280736; cov_it_check(2,3) = 0.000665735;
311  cov_it_check(3,1) = 0.00238938; cov_it_check(3,2) = 0.000665735; cov_it_check(3,3) = 0.00775776;
312  CPPUNIT_ASSERT_EQUAL(approxEqual(posterior_iteratedextendedkalman->ExpectedValueGet(), mean_it_check, epsilon_large),true);
313  CPPUNIT_ASSERT_EQUAL(approxEqual(posterior_iteratedextendedkalman->CovarianceGet(), cov_it_check, epsilon),true);
314 
315  // bs_check
316  Pdf<ColumnVector> * posterior_bootstrap = my_filter_bootstrap->PostGet();
317  ColumnVector mean_bs_check(STATE_SIZE);
318  mean_bs_check=mobile_robot.GetState();
319  //mean_bs_check(1) = mobile_robot_state(1); mean_bs_check(2) = mobile_robot_state(2); mean_bs_check(3) = mobile_robot_state(3);
320  SymmetricMatrix cov_bs_check(STATE_SIZE);
321  cov_bs_check = 0.0;
322  cov_bs_check(1,1) = PRIOR_COV_X;
323  CPPUNIT_ASSERT_EQUAL(approxEqual(posterior_bootstrap->ExpectedValueGet(), mean_bs_check, epsilon_large),true);
324  CPPUNIT_ASSERT_EQUAL(approxEqual(posterior_bootstrap->CovarianceGet(), cov_bs_check, epsilon),true);
325 
326  // ep_check
327  /*
328  Pdf<ColumnVector> * posterior_ekparticle = my_filter_ekparticle->PostGet();
329  cout << " Posterior Mean = " << endl << posterior_ekparticle->ExpectedValueGet() << endl
330  << " Covariance = " << endl << posterior_ekparticle->CovarianceGet() << "" << endl;
331  ColumnVector mean_ep_check(STATE_SIZE);
332  //mean_ep_check(1) = 6.64581; mean_ep_check(2) = -7.05499; mean_ep_check(3) = -0.76974;
333  mean_ep_check=mobile_robot.GetState();
334  SymmetricMatrix cov_ep_check(STATE_SIZE);
335  cov_ep_check(1,1) = 0.0160492; cov_ep_check(1,2) = 0.000193798; cov_ep_check(1,3) = 0.0013101;
336  cov_ep_check(2,1) = 0.000193798; cov_ep_check(2,2) = 0.000289425; cov_ep_check(2,3) = 0.000701263;
337  cov_ep_check(3,1) = 0.0013101; cov_ep_check(3,2) = 0.000701263; cov_ep_check(3,3) = 0.00682061;
338  cout << "mean_ep_check " << mean_ep_check << endl;
339  cout << "cov_ep_check " << cov_ep_check << endl;
340  CPPUNIT_ASSERT_EQUAL(approxEqual(posterior_ekparticle->ExpectedValueGet(), mean_ep_check, epsilon_huge),true);
341  CPPUNIT_ASSERT_EQUAL(approxEqual(posterior_ekparticle->CovarianceGet(), cov_ep_check, epsilon_large),true);
342  */
343  // mixtureBoostrapFilter check
344  posterior_mixtureBootstrap = my_filter_mixtureBootstrap->PostGet();
345  ColumnVector mean_mbs_check(STATE_SIZE);
346  //mean_mbs_check(1) = 6.64581; mean_mbs_check(2) = -7.05499; mean_mbs_check(3) = -0.76974;
347  mean_mbs_check(1) = mobile_robot_state(1); mean_mbs_check(2) = mobile_robot_state(2); mean_mbs_check(3) = mobile_robot_state(3);
348  //cout << "mixture weights:" << endl;
349  vector<Probability> weights= dynamic_cast<Mixture<ColumnVector> *>(posterior_mixtureBootstrap)->WeightsGet();
350  ColumnVector exp;
351  for(int i = 0 ; i< dynamic_cast<Mixture<ColumnVector> *>(posterior_mixtureBootstrap)->NumComponentsGet(); i++ )
352  {
353  //cout << "weight component " << i << ": " << weights[i] << endl;
354  exp= dynamic_cast<Mixture<ColumnVector> *>(posterior_mixtureBootstrap)->ComponentGet(i)->ExpectedValueGet();
355  //cout << "expected value component " << i << ": " << exp << endl;
356  }
357  //cout << "expected value total: " << posterior_mixtureBootstrap->ExpectedValueGet() << endl;
358  //cout << "should be : " << mean_mbs_check << endl;
359  CPPUNIT_ASSERT_EQUAL(approxEqual(posterior_mixtureBootstrap->ExpectedValueGet(), mean_mbs_check, epsilon_huge),true);
360 
361  // closing file stream
362  if(OUTPUT_MIXTURE)
363  {
364  mixtureFile.close();
365  }
366 
367  // delete the filters
368  delete my_filter_extendedkalman;
369  delete my_filter_iteratedextendedkalman;
370  delete my_filter_bootstrap;
371  delete my_filter_ekparticle;
372  delete my_filter_mixtureBootstrap;
373 }
374 
375 void
377 {
378  int num_states = 20;
379  int num_cond_args = 1;
380  /****************************
381  * Discrete system model *
382  ***************************/
383  int cond_arg_dims[num_cond_args];
384  cond_arg_dims[0] = num_states;
385  DiscreteConditionalPdf sys_pdf(num_states,num_cond_args,cond_arg_dims); // no inputs
386  std::vector<int> cond_args(num_cond_args);
387  double prob_diag = 0.9;
388  double prob_nondiag = (1-prob_diag)/(num_states-1);
389  for (int state_kMinusOne = 0 ; state_kMinusOne < num_states ; state_kMinusOne++)
390  {
391  cond_args[0] = state_kMinusOne;
392  for (int state_k = 0 ; state_k < num_states ; state_k++)
393  {
394  if (state_kMinusOne == state_k) sys_pdf.ProbabilitySet(prob_diag,state_k,cond_args);
395  else sys_pdf.ProbabilitySet(prob_nondiag,state_k,cond_args);
396  }
397  }
398  DiscreteSystemModel sys_model(&sys_pdf);
399 
400  /*********************************
401  * Initialise measurement model *
402  ********************************/
403 
404  // Construct the measurement noise (a scalar in this case)
405  ColumnVector measNoise_Mu(MEAS_SIZE);
406  measNoise_Mu(1) = MU_MEAS_NOISE;
407 
408  SymmetricMatrix measNoise_Cov(MEAS_SIZE);
409  measNoise_Cov(1,1) = SIGMA_MEAS_NOISE;
410  Gaussian measurement_uncertainty(measNoise_Mu, measNoise_Cov);
411 
412  // create the model
413  ConditionalUniformMeasPdf1d meas_pdf(measurement_uncertainty);
415 
416  /****************************
417  * Uniform prior DENSITY *
418  ***************************/
419  DiscretePdf prior(num_states); //equal probability is set for all classed
420 
421  /******************************
422  * Construction of the Filter *
423  ******************************/
424  HistogramFilter<ColumnVector> filter(&prior);
425  DiscretePdf * prior_test = filter.PostGet();
426 
427  /***************************
428  * initialise MOBILE ROBOT *
429  **************************/
430  // Model of mobile robot in world with one wall
431  // The model is used to simultate the distance measurements.
432  MobileRobot mobile_robot;
433  ColumnVector input(2);
434  input(1) = 0.1;
435  input(2) = 0.0;
436 
437 
438  /*******************
439  * ESTIMATION LOOP *
440  *******************/
441  unsigned int time_step;
442  for (time_step = 0; time_step < NUM_TIME_STEPS-1; time_step++)
443  {
444  // DO ONE STEP WITH MOBILE ROBOT
445  mobile_robot.Move(input);
446  // DO ONE MEASUREMENT
447  ColumnVector measurement = mobile_robot.Measure();
448  // change sign of measurement (measurement model returns negative value)
449  measurement(1) = 0-measurement(1);
450  // UPDATE FILTER
451  filter.Update(&sys_model,&meas_model,measurement);
452  } // estimation loop
453 
454  DiscretePdf * posterior = filter.PostGet();
455  for (int state=0; state< num_states; state++)
456  {
457  //cout << state << ": " << posterior->ProbabilityGet(state) << endl;
458  if (state== (int)(mobile_robot.GetState()(2)) ) CPPUNIT_ASSERT(posterior->ProbabilityGet(state) >0.9);
459  else CPPUNIT_ASSERT(posterior->ProbabilityGet(state) <0.1);
460  }
461 }
virtual MatrixWrapper::SymmetricMatrix CovarianceGet() const
Get the Covariance Matrix E[(x - E[x])^2] of the Analytic pdf.
Definition: gaussian.cpp:187
MatrixWrapper::ColumnVector GetState()
#define PRIOR_MU_X2
Class representing a PDF on a discrete variable.
Definition: discretepdf.h:34
Particular particle filter : Proposal PDF = SystemPDF.
virtual MatrixWrapper::ColumnVector ExpectedValueGet() const
Get the expected value E[x] of the pdf.
Definition: gaussian.cpp:181
T ExpectedValueGet() const
Get the expected value E[x] of the pdf.
#define PRIOR_COV_Y4
#define MU_MEAS_NOISE
#define PRIOR_COV_X3
double epsilon
#define SIGMA_MEAS_NOISE
Class PDF: Virtual Base class representing Probability Density Functions.
Definition: pdf.h:53
Class representing the histogram filter.
This is a class simulating a mobile robot.
Definition: mobile_robot.h:47
#define PRIOR_MU_X3
virtual MatrixWrapper::SymmetricMatrix CovarianceGet() const
Get the Covariance Matrix E[(x - E[x])^2] of the Analytic pdf.
Probability ProbabilityGet(const int &state) const
Implementation of virtual base class method.
bool SampleFrom(vector< Sample< MatrixWrapper::ColumnVector > > &list_samples, const int num_samples, int method=DEFAULT, void *args=NULL) const
#define PRIOR_COV_THETA4
MatrixWrapper::ColumnVector Measure()
#define PRIOR_COV_X1
#define MEAS_SIZE
Class representing Gaussian (or normal density)
Definition: gaussian.h:27
#define NUM_ITERATIONS
#define MU_SYSTEM_NOISE_X
#define LIN_SPEED
#define PRIOR_MU_THETA2
#define PRIOR_COV_X4
#define OUTPUT_MIXTURE
Particular mixture particle filter : Proposal PDF = SystemPDF.
#define ROT_SPEED
Particle filter using EKF for proposal step.
#define RICO_WALL
#define MU_SYSTEM_NOISE_THETA
#define RESAMPLE_THRESHOLD
#define SIGMA_SYSTEM_NOISE_THETA
virtual Pdf< StateVar > * PostGet()
Get Posterior density.
Definition: filter.cpp:126
#define PRIOR_COV_Y3
#define STATE_SIZE
#define PRIOR_COV_THETA2
#define INPUT_SIZE
#define RESAMPLE_PERIOD
#define PRIOR_COV_Y1
Class representing a mixture of PDFs, the mixture can contain different.
Definition: mixture.h:48
#define PRIOR_COV_THETA
#define PRIOR_COV_Y
virtual DiscretePdf * PostGet()
Get Posterior density.
virtual T ExpectedValueGet() const
Get the expected value E[x] of the pdf.
void Move(MatrixWrapper::ColumnVector inputs)
#define PRIOR_MU_THETA3
#define PRIOR_MU_THETA1
Monte Carlo Pdf: Sample based implementation of Pdf.
Definition: mcpdf.h:49
#define PRIOR_COV_THETA1
Class for analytic system models with additive Gauss. uncertainty.
#define PRIOR_MU_X
#define PRIOR_MU_THETA
#define PRIOR_COV_X
Abstract Class representing all FULLY Discrete Conditional PDF&#39;s.
#define PRIOR_MU_Y1
#define PRIOR_COV_X2
Class for linear analytic measurementmodels with additive gaussian noise.
#define PRIOR_MU_Y3
#define CHOLESKY
Class for discrete System Models.
#define SIGMA_SYSTEM_NOISE_X
const unsigned int NUM_SAMPLES
Definition: pdf_test.cpp:37
#define PRIOR_MU_Y
#define PRIOR_MU_Y4
virtual bool Update(SystemModel< StateVar > *const sysmodel, const StateVar &u, MeasurementModel< MeasVar, StateVar > *const measmodel, const MeasVar &z, const StateVar &s)
Full Update (system with inputs/sensing params)
Definition: filter.h:56
#define PRIOR_MU_Y2
#define PRIOR_COV_THETA3
#define PRIOR_COV_Y2
bool approxEqual(double a, double b, double epsilon)
Definition: approxEqual.cpp:20
bool ListOfSamplesSet(const vector< WeightedSample< T > > &list_of_samples)
Set the list of weighted samples.
void ProbabilitySet(const double &prob, const int &input, const std::vector< int > &condargs) const
Set the probability (Typical for discrete Pdf&#39;s)
#define MU_SYSTEM_NOISE_Y
#define DELTA_T
CPPUNIT_TEST_SUITE_REGISTRATION(Complete_FilterTest)
#define PRIOR_MU_X1
#define PRIOR_MU_X4
#define SIGMA_SYSTEM_NOISE_Y
#define NUM_TIME_STEPS


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:58