test_kalman_smoother.cpp
Go to the documentation of this file.
1 // $Id: test_kalman_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 
27 
31 
32 #include "../compare_filters/nonlinearanalyticconditionalgaussianmobile.h"
33 #include "../mobile_robot.h"
34 
37 
38 #include <iostream>
39 #include <fstream>
40 
41 // Include file with properties
42 #include "../examples/mobile_robot_wall_cts.h"
43 
44 using namespace MatrixWrapper;
45 using namespace BFL;
46 using namespace std;
47 
48 /* The purpose of this program is to construct a filter for the problem
49  of localisation of a mobile robot equipped with an ultrasonic sensor.
50  In this case the orientation is known, which simplifies the model considerably:
51  The system model will become linear.
52  The ultrasonic measures the distance to the wall (it can be switched off:
53  see mobile_robot_wall_cts.h)
54 
55  The necessary SYSTEM MODEL is:
56 
57  x_k = x_{k-1} + v_{k-1} * cos(theta) * delta_t
58  y_k = y_{k-1} + v_{k-1} * sin(theta) * delta_t
59 
60  The used MEASUREMENT MODEL:
61  measuring the (perpendicular) distance z to the wall y = ax + b
62 
63  set WALL_CT = 1/sqrt(pow(a,2) + 1)
64  z = WALL_CT * a * x - WALL_CT * y + WALL_CT * b + GAUSSIAN_NOISE
65  or Z = H * X_k + J * U_k
66 
67  where
68 
69  H = [ WALL_CT * a - WALL_CT 0 ]
70  and GAUSSIAN_NOISE = N((WALL_CT * b), SIGMA_MEAS_NOISE)
71 
72 */
73 
74 
75 int main(int argc, char** argv)
76 {
77  cerr << "==================================================" << endl
78  << "Test of different smooters" << endl
79  << "Mobile robot localisation example" << endl
80  << "==================================================" << endl;
81 
82  /***********************
83  * PREPARE FILESTREAMS *
84  **********************/
85  ofstream fout_time, fout_E, fout_cov, fout_meas, fout_states, fout_particles, fout_numparticles, fout_E_smooth, fout_cov_smooth, fout_time_smooth;
86 
87  fout_time.open("time.out");
88  fout_E.open("E.out");
89  fout_cov.open("cov.out");
90  fout_meas.open("meas.out");
91  fout_states.open("states.out");
92  fout_E_smooth.open("Esmooth.out");
93  fout_cov_smooth.open("covsmooth.out");
94  fout_time_smooth.open("timesmooth.out");
95 
96  /****************************
97  * NonLinear system model *
98  ***************************/
99 
100  // create gaussian
101  ColumnVector sys_noise_Mu(STATE_SIZE);
102  sys_noise_Mu = 0.0;
103  sys_noise_Mu(1) = MU_SYSTEM_NOISE_X;
104  sys_noise_Mu(2) = MU_SYSTEM_NOISE_Y;
105  sys_noise_Mu(3) = MU_SYSTEM_NOISE_THETA;
106 
107  SymmetricMatrix sys_noise_Cov(STATE_SIZE);
108  sys_noise_Cov = 0.0;
109  sys_noise_Cov(1,1) = SIGMA_SYSTEM_NOISE_X;
110  sys_noise_Cov(1,2) = 0.0;
111  sys_noise_Cov(1,3) = 0.0;
112  sys_noise_Cov(2,1) = 0.0;
113  sys_noise_Cov(2,2) = SIGMA_SYSTEM_NOISE_Y;
114  sys_noise_Cov(2,3) = 0.0;
115  sys_noise_Cov(3,1) = 0.0;
116  sys_noise_Cov(3,2) = 0.0;
117  sys_noise_Cov(3,3) = SIGMA_SYSTEM_NOISE_THETA;
118 
119  Gaussian system_Uncertainty(sys_noise_Mu, sys_noise_Cov);
120 
121  // create the model
122  NonLinearAnalyticConditionalGaussianMobile sys_pdf(system_Uncertainty);
123  AnalyticSystemModelGaussianUncertainty sys_model(&sys_pdf);
124 
125  /*********************************
126  * Initialise measurement model *
127  ********************************/
128  // Fill up H
129  double wall_ct = 2/(sqrt(pow(RICO_WALL,2.0) + 1));
130  Matrix H(MEAS_SIZE,STATE_SIZE);
131  H = 0.0;
132  H(1,1) = wall_ct * RICO_WALL;
133  H(1,2) = 0 - wall_ct;
134 
135  // Construct the measurement noise (a scalar in this case)
136  ColumnVector MeasNoise_Mu(MEAS_SIZE);
137  SymmetricMatrix MeasNoise_Cov(MEAS_SIZE);
138  MeasNoise_Mu(1) = MU_MEAS_NOISE;
139  MeasNoise_Cov(1,1) = SIGMA_MEAS_NOISE;
140 
141  Gaussian measurement_Uncertainty(MeasNoise_Mu,MeasNoise_Cov);
142 
143  // create the model
144  LinearAnalyticConditionalGaussian meas_pdf(H, measurement_Uncertainty);
146 
147 
148  /****************************
149  * Linear prior DENSITY *
150  ***************************/
151  // Continuous Gaussian prior (for Kalman filters)
152  ColumnVector prior_mu(STATE_SIZE);
153  SymmetricMatrix prior_sigma(STATE_SIZE);
154  prior_mu(1) = PRIOR_MU_X;
155  prior_mu(2) = PRIOR_MU_Y;
156  prior_sigma = 0.0;
157  prior_sigma(1,1) = PRIOR_COV_X;
158  prior_sigma(2,2) = PRIOR_COV_Y;
159  prior_sigma(3,3) = PRIOR_COV_THETA;
160  Gaussian prior_cont(prior_mu,prior_sigma);
161 
162 
163  cout<< "Prior initialised"<< "" << endl;
164  cout << "Prior Mean = " << endl << prior_cont.ExpectedValueGet() << endl
165  << "Covariance = " << endl << prior_cont.CovarianceGet() << endl;
166 
167  /******************************
168  * Construction of the Filter *
169  ******************************/
170  ExtendedKalmanFilter filter(&prior_cont);
171 
172 
173 
174  /***************************
175  * initialise MOBILE ROBOT *
176  **************************/
177  // Model of mobile robot in world with one wall
178  // The model is used to simultate the distance measurements.
179  MobileRobot mobile_robot;
180  ColumnVector input(2);
181  input(1) = 0.1;
182  input(2) = 0.0;
183 
184  /***************************
185  * vector in which all posteriors will be stored*
186  **************************/
187  vector<Gaussian> posteriors(NUM_TIME_STEPS);
188  vector<Gaussian>::iterator posteriors_it = posteriors.begin();
189 
190  /*******************
191  * ESTIMATION LOOP *
192  *******************/
193  cout << "MAIN: Starting estimation" << endl;
194  unsigned int time_step;
195  for (time_step = 0; time_step < NUM_TIME_STEPS; time_step++)
196  {
197  // write date in files
198  fout_time << time_step << ";" << endl;
199  fout_meas << mobile_robot.Measure()(1) << ";" << endl;
200  fout_states << mobile_robot.GetState()(1) << "," << mobile_robot.GetState()(2) << ","
201  << mobile_robot.GetState()(3) << ";" << endl;
202 
203  // write posterior to file
204  Gaussian * posterior = (Gaussian*)(filter.PostGet());
205  fout_E << posterior->ExpectedValueGet()(1) << "," << posterior->ExpectedValueGet()(2)<< ","
206  << posterior->ExpectedValueGet()(3) << ";" << endl;
207  fout_cov << posterior->CovarianceGet()(1,1) << "," << posterior->CovarianceGet()(1,2) << ","
208  << posterior->CovarianceGet()(1,3) << "," << posterior->CovarianceGet()(2,2) << ","
209  << posterior->CovarianceGet()(2,3) << "," << posterior->CovarianceGet()(3,3) << ";" << endl;
210 
211  // DO ONE STEP WITH MOBILE ROBOT
212  mobile_robot.Move(input);
213 
214  if ((time_step+1)%10 == 0){
215  // DO ONE MEASUREMENT
216  ColumnVector measurement = mobile_robot.Measure();
217 
218  // UPDATE FILTER
219  filter.Update(&sys_model,input,&meas_model,measurement);
220  }
221  else{
222  filter.Update(&sys_model,input);
223  }
224 
225  //Pdf<ColumnVector> * posterior = filter.PostGet();
226  // make copy of posterior
227  *posteriors_it = *posterior;
228 
229  posteriors_it++;
230  } // estimation loop
231 
232 
233  Pdf<ColumnVector> * posterior = filter.PostGet();
234  // write data in files
235  fout_time << time_step << ";" << endl;
236  fout_meas << mobile_robot.Measure()(1) << ";" << endl;
237  fout_states << mobile_robot.GetState()(1) << "," << mobile_robot.GetState()(2) << ","
238  << mobile_robot.GetState()(3) << ";" << endl;
239 
240  // write posterior to file
241  fout_E << posterior->ExpectedValueGet()(1) << "," << posterior->ExpectedValueGet()(2)<< ","
242  << posterior->ExpectedValueGet()(3) << ";" << endl;
243  fout_cov << posterior->CovarianceGet()(1,1) << "," << posterior->CovarianceGet()(1,2) << ","
244  << posterior->CovarianceGet()(1,3) << "," << posterior->CovarianceGet()(2,2) << ","
245  << posterior->CovarianceGet()(2,3) << "," << posterior->CovarianceGet()(3,3) << ";" << endl;
246 
247  cout << "After " << time_step+1 << " timesteps " << endl;
248  cout << " Posterior Mean = " << endl << posterior->ExpectedValueGet() << endl
249  << " Covariance = " << endl << posterior->CovarianceGet() << "" << endl;
250 
251 
252  cout << "======================================================" << endl
253  << "End of the filter for mobile robot localisation" << endl
254  << "======================================================"
255  << endl;
256 
257 
258  /***************************************
259  * Construction of the Backward Filter *
260  **************************************/
261 RauchTungStriebel backwardfilter((Gaussian*)posterior);
262 
263  fout_time_smooth << time_step << ";" << endl;
264  // write posterior to file
265  fout_E_smooth << posterior->ExpectedValueGet()(1) << "," << posterior->ExpectedValueGet()(2)<< ","
266  << posterior->ExpectedValueGet()(3) << ";" << endl;
267  fout_cov_smooth << posterior->CovarianceGet()(1,1) << "," << posterior->CovarianceGet()(1,2) << ","
268  << posterior->CovarianceGet()(1,3) << "," << posterior->CovarianceGet()(2,2) << ","
269  << posterior->CovarianceGet()(2,3) << "," << posterior->CovarianceGet()(3,3) << ";" << endl;
270 
271  /*******************
272  * ESTIMATION LOOP *
273  *******************/
274  cout << "======================================================" << endl
275  << "Start of the smoother for mobile robot localisation" << endl
276  << "======================================================"
277  << endl;
278  for (time_step = NUM_TIME_STEPS-1; time_step+1 > 0 ; time_step--)
279  {
280  posteriors_it--;
281  // UPDATE BACKWARDFILTER
282  Gaussian filtered(posteriors_it->ExpectedValueGet(),posteriors_it->CovarianceGet());
283  backwardfilter.Update(&sys_model,input, &filtered);
284  Pdf<ColumnVector> * posterior = backwardfilter.PostGet();
285 
286  fout_time_smooth << time_step << ";" << endl;
287  // write posterior to file
288  fout_E_smooth << posterior->ExpectedValueGet()(1) << "," << posterior->ExpectedValueGet()(2)<< ","
289  << posterior->ExpectedValueGet()(3) << ";" << endl;
290  fout_cov_smooth << posterior->CovarianceGet()(1,1) << "," << posterior->CovarianceGet()(1,2) << ","
291  << posterior->CovarianceGet()(1,3) << "," << posterior->CovarianceGet()(2,2) << ","
292  << posterior->CovarianceGet()(2,3) << "," << posterior->CovarianceGet()(3,3) << ";" << endl;
293 
294  // make copy of posterior
295  posteriors_it->ExpectedValueSet(posterior->ExpectedValueGet());
296  posteriors_it->CovarianceSet(posterior->CovarianceGet());
297 
298  } // estimation loop
299 
300  cout << "After Smoothing first timestep " << endl;
301  cout << " Posterior Mean = " << endl << posteriors_it->ExpectedValueGet() << endl
302  << " Covariance = " << endl << posteriors_it->CovarianceGet() << "" << endl;
303 
304 
305 
306  cout << "======================================================" << endl
307  << "End of the Kalman smoother for mobile robot localisation" << endl
308  << "======================================================"
309  << endl;
310  return 0;
311 
312  /****************************
313  * CLOSE FILESTREAMS
314  ***************************/
315  fout_time.close();
316  fout_E.close();
317  fout_cov.close();
318  fout_meas.close();
319  fout_states.close();
320  fout_time_smooth.close();
321  fout_E_smooth.close();
322  fout_cov_smooth.close();
323 }
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()
virtual MatrixWrapper::ColumnVector ExpectedValueGet() const
Get the expected value E[x] of the pdf.
Definition: gaussian.cpp:181
#define MU_MEAS_NOISE
#define SIGMA_MEAS_NOISE
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.
MatrixWrapper::ColumnVector Measure()
Class representing all Rauch-Tung-Striebel backward filters.
#define MEAS_SIZE
Class representing Gaussian (or normal density)
Definition: gaussian.h:27
virtual Pdf< StateVar > * PostGet()
Get Posterior density.
#define MU_SYSTEM_NOISE_X
int main(int argc, char **argv)
#define RICO_WALL
#define MU_SYSTEM_NOISE_THETA
#define SIGMA_SYSTEM_NOISE_THETA
#define STATE_SIZE
#define PRIOR_COV_THETA
#define PRIOR_COV_Y
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.
void Move(MatrixWrapper::ColumnVector inputs)
Class for analytic system models with additive Gauss. uncertainty.
#define PRIOR_MU_X
virtual Gaussian * PostGet()
Get Posterior density.
#define PRIOR_COV_X
Class for linear analytic measurementmodels with additive gaussian noise.
#define SIGMA_SYSTEM_NOISE_X
#define PRIOR_MU_Y
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 MU_SYSTEM_NOISE_Y
#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:59