test_nonlinear_smoother.cpp
Go to the documentation of this file.
1 // $Id: test_nonlinear_smoother.cpp 5925 2006-03-14 21:23:49Z tdelaet $
2 // Copyright (C) 2006 Tinne De Laet <first dot last 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 Lesser General Public License as published by
6 // the Free Software Foundation; either version 2.1 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 Lesser General Public License for more details.
13 //
14 // You should have received a copy of the GNU Lesser 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 /* Demonstration program for the Bayesian Filtering Library.
19  Mobile robot localization with respect to wall with different possibilities for filter
20 */
21 
22 
24 #include <filter/bootstrapfilter.h>
25 
28 
32 #include <pdf/mcpdf.h>
33 #include <pdf/pdf.h>
34 
35 #include "nonlinearanalyticconditionalgaussianmobile.h"
36 #include "mobile_robot.h"
37 
40 
41 #include <iostream>
42 #include <fstream>
43 
44 using namespace MatrixWrapper;
45 using namespace BFL;
46 using namespace std;
47 
48 
49 
50 /* The purpose of this program is to construct a smoother (consisting of a
51  forward and a backward filter) for the problem
52  of localisation of a mobile robot equipped with an ultrasonic sensor.
53  The ultrasonic measures the distance to the wall (it can be switched off:
54  see mobile_robot_wall_cts.h)
55 
56  The necessary SYSTEM MODEL is:
57 
58  x_k = x_{k-1} + v_{k-1} * cos(theta) * delta_t
59  y_k = y_{k-1} + v_{k-1} * sin(theta) * delta_t
60 
61  The used MEASUREMENT MODEL:
62  measuring the (perpendicular) distance z to the wall y = ax + b
63 
64  set WALL_CT = 1/sqrt(pow(a,2) + 1)
65  z = WALL_CT * a * x - WALL_CT * y + WALL_CT * b + GAUSSIAN_NOISE
66  or Z = H * X_k + J * U_k
67 
68  where
69 
70  H = [ WALL_CT * a - WALL_CT 0 ]
71  and GAUSSIAN_NOISE = N((WALL_CT * b), SIGMA_MEAS_NOISE)
72 
73 */
74 
75 #define KALMAN 1
76 #define BOOTSTRAP 2
77 
78 int main(int argc, char** argv)
79 {
80  cerr << "==================================================" << endl
81  << "Test of different smooters" << endl
82  << "Mobile robot localisation example" << endl
83  << "==================================================" << endl;
84 
85  int smoother_name;
86  if (!(argc== 2 ))
87  {
88  cout << "Please provide one argument. Possible arguments are:" << endl
89  << " kalman_smoother" << endl
90  << " bootstrap_smoother" << endl;
91  return 0;
92  }
93  else {
94  string argument = argv[1];
95  if (argument == "kalman_filter") smoother_name = KALMAN;
96  else if (argument == "bootstrap_filter") smoother_name = BOOTSTRAP;
97  else
98  {
99  cout << "Please provide another argument. Possible arguments are:" << endl
100  << " kalman_filter" << endl
101  << " bootstrap_filter" << endl;
102  return 0 ;
103  }
104  }
105  /***********************
106  * PREPARE FILESTREAMS *
107  **********************/
108  ofstream fout_time, fout_E, fout_cov, fout_meas, fout_states, fout_particles, fout_numparticles, fout_E_smooth, fout_cov_smooth, fout_time_smooth, fout_particles_smooth, fout_numparticles_smooth;
109 
110  fout_time.open("time.out");
111  fout_E.open("E.out");
112  fout_cov.open("cov.out");
113  fout_meas.open("meas.out");
114  fout_states.open("states.out");
115  fout_E_smooth.open("Esmooth.out");
116  fout_cov_smooth.open("covsmooth.out");
117  fout_time_smooth.open("timesmooth.out");
118 
119  if (smoother_name == BOOTSTRAP )
120  {
121  fout_particles.open("particles.out");
122  fout_numparticles.open("numparticles.out");
123  fout_particles_smooth.open("particlessmooth.out");
124  fout_numparticles_smooth.open("numparticlessmooth.out");
125  }
126 
127 
128  /****************************
129  * Linear system model *
130  ***************************/
131 
132  // create gaussian
133  ColumnVector sysNoise_Mu(3);
134  sysNoise_Mu(1) = 0.0;
135  sysNoise_Mu(2) = 0.0;
136  sysNoise_Mu(3) = 0.0;
137 
138  SymmetricMatrix sysNoise_Cov(3);
139  sysNoise_Cov(1,1) = pow(0.05,2);
140  sysNoise_Cov(1,2) = 0.0;
141  sysNoise_Cov(1,3) = 0.0;
142  sysNoise_Cov(2,1) = 0.0;
143  sysNoise_Cov(2,2) = pow(0.05,2);
144  sysNoise_Cov(2,3) = 0.0;
145  sysNoise_Cov(3,1) = 0.0;
146  sysNoise_Cov(3,2) = 0.0;
147  sysNoise_Cov(3,3) = pow(0.03,2);
148 
149  Gaussian system_Uncertainty(sysNoise_Mu, sysNoise_Cov);
150 
151  // create the model
152  NonLinearAnalyticConditionalGaussianMobile sys_pdf(system_Uncertainty);
153  AnalyticSystemModelGaussianUncertainty sys_model(&sys_pdf);
154 
155  /*********************************
156  * Initialise measurement model *
157  ********************************/
158 
159  // create matrix H for linear measurement model
160  Matrix H(1,3);
161  H(1,1) = 0.0;
162  H(1,2) = 2.0;
163  H(1,3) = 0;
164  // Construct the measurement noise (a scalar in this case)
165  ColumnVector measNoise_Mu(1);
166  measNoise_Mu(1) = 0.0;
167 
168  SymmetricMatrix measNoise_Cov(1);
169  measNoise_Cov(1,1) = pow(0.05,2);
170  Gaussian measurement_Uncertainty(measNoise_Mu, measNoise_Cov);
171 
172  // create the model
173  LinearAnalyticConditionalGaussian meas_pdf(H, measurement_Uncertainty);
175 
176 
177  /****************************
178  * Linear prior DENSITY *
179  ***************************/
180  // Continuous Gaussian prior (for Kalman filters)
181  ColumnVector prior_Mu(3);
182  prior_Mu(1) = 1.0;//-1.0;
183  prior_Mu(2) = 0.0;//1.0;
184  prior_Mu(3) = 0.0;
185  SymmetricMatrix prior_Cov(3);
186  prior_Cov(1,1) = 0.1;
187  prior_Cov(1,2) = 0.0;
188  prior_Cov(1,3) = 0.0;
189  prior_Cov(2,1) = 0.0;
190  prior_Cov(2,2) = 1.0;
191  prior_Cov(2,3) = 0.0;
192  prior_Cov(3,1) = 0.0;
193  prior_Cov(3,2) = 0.0;
194  prior_Cov(3,3) = pow(0.8,2);
195  Gaussian prior_cont(prior_Mu,prior_Cov);
196 
197  int NUM_SAMPLES = 1000;
198  vector<Sample<ColumnVector> > prior_samples(NUM_SAMPLES);
199  MCPdf<ColumnVector> prior_discr(NUM_SAMPLES,3);
200  prior_cont.SampleFrom(prior_samples,NUM_SAMPLES,CHOLESKY,NULL);
201  prior_discr.ListOfSamplesSet(prior_samples);
202 
203  cout<< "Prior initialised"<< "" << endl;
204  cout << "Prior Mean = " << endl << prior_cont.ExpectedValueGet() << endl
205  << "Covariance = " << endl << prior_cont.CovarianceGet() << endl;
206 
207  /******************************
208  * Construction of the Filter *
209  ******************************/
210  //ExtendedKalmanFilter filter(&prior_cont);
211  Filter<ColumnVector,ColumnVector> * filter = NULL;
212 
213  switch (smoother_name){
214  case KALMAN:{
215  cout << "Using the Extended Kalman Filter" << endl;
216  filter = new ExtendedKalmanFilter(&prior_cont);
217  break;}
218  case BOOTSTRAP:{
219  cout << "Using the bootstrapfilter, " << NUM_SAMPLES << " samples, dynamic resampling" << endl;
220  filter = new BootstrapFilter<ColumnVector,ColumnVector> (&prior_discr, 0, NUM_SAMPLES/4.0);
221  break;}
222  default:{
223  cout << "Type if filter not recognised on construction" <<endl;
224  return 0 ;}
225  }
226 
227 
228  /***************************
229  * initialise MOBILE ROBOT *
230  **************************/
231  // Model of mobile robot in world with one wall
232  // The model is used to simultate the distance measurements.
233  MobileRobot mobile_robot;
234  ColumnVector input(2);
235  input(1) = 0.1;
236  input(2) = 0.0;
237 
238 
239  /***************************
240  * number of timesteps*
241  **************************/
242  unsigned int num_timesteps = 3;
243 
244  /***************************
245  * vector in which all posteriors will be stored*
246  **************************/
247  // in case of gaussian
248  vector<Gaussian> posteriors_gauss(num_timesteps);
249  vector<Gaussian>::iterator posteriors_it_gauss = posteriors_gauss.begin();
250  // in case of mcpdf
251  vector<MCPdf<ColumnVector> > posteriors_mcpdf(num_timesteps);
252  vector<MCPdf<ColumnVector> >::iterator posteriors_it_mcpdf = posteriors_mcpdf.begin();
253 
254  /*******************
255  * ESTIMATION LOOP *
256  *******************/
257  cout << "MAIN: Starting estimation" << endl;
258  unsigned int time_step;
259  for (time_step = 0; time_step < num_timesteps; time_step++)
260  {
261  // write date in files
262  fout_time << time_step << ";" << endl;
263  fout_meas << mobile_robot.Measure()(1) << ";" << endl;
264  fout_states << mobile_robot.GetState()(1) << "," << mobile_robot.GetState()(2) << ","
265  << mobile_robot.GetState()(3) << ";" << endl;
266 
267  // write posterior to file
268  Pdf<ColumnVector> * posterior = filter->PostGet();
269  fout_E << posterior->ExpectedValueGet()(1) << "," << posterior->ExpectedValueGet()(2)<< ","
270  << posterior->ExpectedValueGet()(3) << ";" << endl;
271  fout_cov << posterior->CovarianceGet()(1,1) << "," << posterior->CovarianceGet()(1,2) << ","
272  << posterior->CovarianceGet()(1,3) << "," << posterior->CovarianceGet()(2,2) << ","
273  << posterior->CovarianceGet()(2,3) << "," << posterior->CovarianceGet()(3,3) << ";" << endl;
274 
275  // write particles to file
276  if (smoother_name == BOOTSTRAP)
277  {
278  fout_numparticles << ((MCPdf<ColumnVector>*)posterior)->NumSamplesGet() << ";" << endl;
279  vector<WeightedSample<ColumnVector> > samples_list = ((MCPdf<ColumnVector>*)posterior)->ListOfSamplesGet() ;
280  vector<WeightedSample<ColumnVector> >::iterator sample;
281  for ( sample = samples_list.begin() ; sample != samples_list.end() ; sample++ )
282  fout_particles << sample->ValueGet()(1) << "," << sample->ValueGet()(2) << ","
283  << sample->ValueGet()(3) << "," << sample->WeightGet() <<";"<<endl;
284  }
285  // DO ONE STEP WITH MOBILE ROBOT
286  mobile_robot.Move(input);
287 
288  if ((time_step+1)%5 == 0){
289  // DO ONE MEASUREMENT
290  ColumnVector measurement = mobile_robot.Measure();
291  // UPDATE FILTER
292  filter->Update(&sys_model,input,&meas_model,measurement);
293  }
294  else{
295  filter->Update(&sys_model,input);
296  }
297 
298  // make copy of posterior
299  //*posteriors_it = (Gaussian)(*posterior);
300  switch (smoother_name){
301  case KALMAN:{
302  *posteriors_it_gauss = *(Gaussian*)(posterior);
303  posteriors_it_gauss++;
304  break;}
305  case BOOTSTRAP:{
306  *posteriors_it_mcpdf = *(MCPdf<ColumnVector>*)(posterior);
307  posteriors_it_mcpdf++;
308  break;}
309  default:{
310  cout << "Type if filter not recognised on construction" <<endl;
311  return 0 ;}
312  }
313  } // estimation loop
314 
315 
316  Pdf<ColumnVector> * posterior = filter->PostGet();
317  // write data in files
318  fout_time << time_step << ";" << endl;
319  fout_meas << mobile_robot.Measure()(1) << ";" << endl;
320  fout_states << mobile_robot.GetState()(1) << "," << mobile_robot.GetState()(2) << ","
321  << mobile_robot.GetState()(3) << ";" << endl;
322 
323  // write posterior to file
324  fout_E << posterior->ExpectedValueGet()(1) << "," << posterior->ExpectedValueGet()(2)<< ","
325  << posterior->ExpectedValueGet()(3) << ";" << endl;
326  fout_cov << posterior->CovarianceGet()(1,1) << "," << posterior->CovarianceGet()(1,2) << ","
327  << posterior->CovarianceGet()(1,3) << "," << posterior->CovarianceGet()(2,2) << ","
328  << posterior->CovarianceGet()(2,3) << "," << posterior->CovarianceGet()(3,3) << ";" << endl;
329  // write particles to file
330  if (smoother_name == BOOTSTRAP)
331  {
332  fout_numparticles << ((MCPdf<ColumnVector>*)posterior)->NumSamplesGet() << ";" << endl;
333  vector<WeightedSample<ColumnVector> > samples_list = ((MCPdf<ColumnVector>*)posterior)->ListOfSamplesGet() ;
334  vector<WeightedSample<ColumnVector> >::iterator sample;
335  for ( sample = samples_list.begin() ; sample != samples_list.end() ; sample++ )
336  fout_particles << sample->ValueGet()(1) << "," << sample->ValueGet()(2) << ","
337  << sample->ValueGet()(3) << "," << sample->WeightGet() <<";"<<endl;
338  }
339 
340  cout << "After " << time_step+1 << " timesteps " << endl;
341  cout << " Posterior Mean = " << endl << posterior->ExpectedValueGet() << endl
342  << " Covariance = " << endl << posterior->CovarianceGet() << "" << endl;
343 
344 
345  cout << "======================================================" << endl
346  << "End of the filter for mobile robot localisation" << endl
347  << "======================================================"
348  << endl;
349 
350 
351  /***************************************
352  * Construction of the Backward Filter *
353  **************************************/
354  BackwardFilter<ColumnVector> * backwardfilter = NULL;
355 
356  switch (smoother_name){
357  case KALMAN:{
358  cout << "Using the RauchTungStriebelSmoother" << endl;
359  backwardfilter = new RauchTungStriebel((Gaussian*)posterior);
360  break;}
361  case BOOTSTRAP:{
362  cout << "Using the particlesmoother, " << NUM_SAMPLES << " samples" << endl;
363  backwardfilter = new ParticleSmoother<ColumnVector>((MCPdf<ColumnVector>*)posterior);
364  break;}
365  default:{
366  cout << "Type if filter not recognised on construction" <<endl;
367  return 0 ;}
368  }
369  fout_time_smooth << time_step << ";" << endl;
370  // write posterior to file
371  fout_E_smooth << posterior->ExpectedValueGet()(1) << "," << posterior->ExpectedValueGet()(2)<< ","
372  << posterior->ExpectedValueGet()(3) << ";" << endl;
373  fout_cov_smooth << posterior->CovarianceGet()(1,1) << "," << posterior->CovarianceGet()(1,2) << ","
374  << posterior->CovarianceGet()(1,3) << "," << posterior->CovarianceGet()(2,2) << ","
375  << posterior->CovarianceGet()(2,3) << "," << posterior->CovarianceGet()(3,3) << ";" << endl;
376  // write particles to file
377  if (smoother_name == BOOTSTRAP)
378  {
379  fout_numparticles_smooth << ((MCPdf<ColumnVector>*)posterior)->NumSamplesGet() << ";" << endl;
380  vector<WeightedSample<ColumnVector> > samples_list = ((MCPdf<ColumnVector>*)posterior)->ListOfSamplesGet() ;
381  vector<WeightedSample<ColumnVector> >::iterator sample;
382  for ( sample = samples_list.begin() ; sample != samples_list.end() ; sample++ )
383  fout_particles_smooth << sample->ValueGet()(1) << "," << sample->ValueGet()(2) << ","
384  << sample->ValueGet()(3) << "," << sample->WeightGet() <<";"<<endl;
385  }
386 
387  /*******************
388  * ESTIMATION LOOP *
389  *******************/
390  cout << "======================================================" << endl
391  << "Start of the smoother for mobile robot localisation" << endl
392  << "======================================================"
393  << endl;
394  for (time_step = num_timesteps-1; time_step+1 > 0 ; time_step--)
395  {
396  //Pdf<ColumnVector> filtered;
397  switch (smoother_name){
398  case KALMAN:{
399  posteriors_it_gauss--;
400  Gaussian filtered = *posteriors_it_gauss;
401  backwardfilter->Update(&sys_model,input, &filtered);
402  break;}
403  case BOOTSTRAP:{
404  posteriors_it_mcpdf--;
405  MCPdf<ColumnVector> filtered = *posteriors_it_mcpdf;
406  cout << "before update" << endl;
407  backwardfilter->Update(&sys_model,input, &filtered);
408  cout << "after update" << endl;
409  break;}
410  default:{
411  cout << "Type if filter not recognised on construction" <<endl;
412  return 0 ;}
413  }
414  // UPDATE BACKWARDFILTER
415  Pdf<ColumnVector> * posterior = backwardfilter->PostGet();
416 
417  fout_time_smooth << time_step << ";" << endl;
418  // write posterior to file
419  fout_E_smooth << posterior->ExpectedValueGet()(1) << "," << posterior->ExpectedValueGet()(2)<< ","
420  << posterior->ExpectedValueGet()(3) << ";" << endl;
421  fout_cov_smooth << posterior->CovarianceGet()(1,1) << "," << posterior->CovarianceGet()(1,2) << ","
422  << posterior->CovarianceGet()(1,3) << "," << posterior->CovarianceGet()(2,2) << ","
423  << posterior->CovarianceGet()(2,3) << "," << posterior->CovarianceGet()(3,3) << ";" << endl;
424  // write particles to file
425  if (smoother_name == BOOTSTRAP)
426  {
427  fout_numparticles_smooth << ((MCPdf<ColumnVector>*)posterior)->NumSamplesGet() << ";" << endl;
428  vector<WeightedSample<ColumnVector> > samples_list = ((MCPdf<ColumnVector>*)posterior)->ListOfSamplesGet() ;
429  vector<WeightedSample<ColumnVector> >::iterator sample;
430  for ( sample = samples_list.begin() ; sample != samples_list.end() ; sample++ )
431  fout_particles_smooth << sample->ValueGet()(1) << "," << sample->ValueGet()(2) << ","
432  << sample->ValueGet()(3) << "," << sample->WeightGet() <<";"<<endl;
433  }
434 
435  // make copy of posterior
436  //*posteriors_it = (Gaussian)(*posterior);
437  switch (smoother_name){
438  case KALMAN:{
439  *posteriors_it_gauss = *(Gaussian*)(posterior);
440  break;}
441  case BOOTSTRAP:{
442  *posteriors_it_mcpdf = *(MCPdf<ColumnVector>*)(posterior);
443  break;}
444  default:{
445  cout << "Type if filter not recognised on construction" <<endl;
446  return 0 ;}
447  }
448 
449  } // estimation loop
450 
451 
452  // delete the filter
453  delete filter;
454  delete backwardfilter;
455 
456  cout << "======================================================" << endl
457  << "End of the backward filter for mobile robot localisation" << endl
458  << "======================================================"
459  << endl;
460 
461  /****************************
462  * CLOSE FILESTREAMS
463  ***************************/
464  fout_time.close();
465  fout_E.close();
466  fout_cov.close();
467  fout_meas.close();
468  fout_states.close();
469  fout_time_smooth.close();
470  fout_E_smooth.close();
471  fout_cov_smooth.close();
472  if (smoother_name == BOOTSTRAP )
473  {
474  fout_particles.close();
475  fout_numparticles.close();
476  fout_particles_smooth.close();
477  fout_numparticles_smooth.close();
478  }
479  return 0;
480 }
#define KALMAN
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()
Particular particle filter : Proposal PDF = SystemPDF.
virtual MatrixWrapper::ColumnVector ExpectedValueGet() const
Get the expected value E[x] of the pdf.
Definition: gaussian.cpp:181
Class PDF: Virtual Base class representing Probability Density Functions.
Definition: pdf.h:53
This is a class simulating a mobile robot.
Definition: mobile_robot.h:47
virtual MatrixWrapper::SymmetricMatrix CovarianceGet() const
Get the Covariance Matrix E[(x - E[x])^2] of the Analytic pdf.
bool SampleFrom(vector< Sample< MatrixWrapper::ColumnVector > > &list_samples, const int num_samples, int method=DEFAULT, void *args=NULL) const
MatrixWrapper::ColumnVector Measure()
Class representing all Rauch-Tung-Striebel backward filters.
Class representing Gaussian (or normal density)
Definition: gaussian.h:27
Virtual Baseclass representing all bayesian backward filters.
virtual Pdf< StateVar > * PostGet()
Get Posterior density.
virtual Pdf< StateVar > * PostGet()
Get Posterior density.
Definition: filter.cpp:126
virtual bool Update(SystemModel< StateVar > *const sysmodel, const StateVar &u, Pdf< StateVar > *const filtered_post)
Full Update (system with inputs)
virtual T ExpectedValueGet() const
Get the expected value E[x] of the pdf.
Class representing a particle backward filter.
void Move(MatrixWrapper::ColumnVector inputs)
int main(int argc, char **argv)
Monte Carlo Pdf: Sample based implementation of Pdf.
Definition: mcpdf.h:49
Class for analytic system models with additive Gauss. uncertainty.
Class for linear analytic measurementmodels with additive gaussian noise.
#define CHOLESKY
#define BOOTSTRAP
const unsigned int NUM_SAMPLES
Definition: pdf_test.cpp:37
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
bool ListOfSamplesSet(const vector< WeightedSample< T > > &list_of_samples)
Set the list of weighted samples.


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