35 #include "nonlinearanalyticconditionalgaussianmobile.h" 78 int main(
int argc,
char** argv)
80 cerr <<
"==================================================" << endl
81 <<
"Test of different smooters" << endl
82 <<
"Mobile robot localisation example" << endl
83 <<
"==================================================" << endl;
88 cout <<
"Please provide one argument. Possible arguments are:" << endl
89 <<
" kalman_smoother" << endl
90 <<
" bootstrap_smoother" << endl;
94 string argument = argv[1];
95 if (argument ==
"kalman_filter") smoother_name =
KALMAN;
96 else if (argument ==
"bootstrap_filter") smoother_name =
BOOTSTRAP;
99 cout <<
"Please provide another argument. Possible arguments are:" << endl
100 <<
" kalman_filter" << endl
101 <<
" bootstrap_filter" << endl;
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;
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");
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");
133 ColumnVector sysNoise_Mu(3);
134 sysNoise_Mu(1) = 0.0;
135 sysNoise_Mu(2) = 0.0;
136 sysNoise_Mu(3) = 0.0;
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);
149 Gaussian system_Uncertainty(sysNoise_Mu, sysNoise_Cov);
165 ColumnVector measNoise_Mu(1);
166 measNoise_Mu(1) = 0.0;
168 SymmetricMatrix measNoise_Cov(1);
169 measNoise_Cov(1,1) = pow(0.05,2);
170 Gaussian measurement_Uncertainty(measNoise_Mu, measNoise_Cov);
181 ColumnVector prior_Mu(3);
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);
198 vector<Sample<ColumnVector> > prior_samples(NUM_SAMPLES);
203 cout<<
"Prior initialised"<<
"" << endl;
205 <<
"Covariance = " << endl << prior_cont.
CovarianceGet() << endl;
213 switch (smoother_name){
215 cout <<
"Using the Extended Kalman Filter" << endl;
219 cout <<
"Using the bootstrapfilter, " << NUM_SAMPLES <<
" samples, dynamic resampling" << endl;
223 cout <<
"Type if filter not recognised on construction" <<endl;
234 ColumnVector input(2);
242 unsigned int num_timesteps = 3;
248 vector<Gaussian> posteriors_gauss(num_timesteps);
249 vector<Gaussian>::iterator posteriors_it_gauss = posteriors_gauss.begin();
251 vector<MCPdf<ColumnVector> > posteriors_mcpdf(num_timesteps);
252 vector<MCPdf<ColumnVector> >::iterator posteriors_it_mcpdf = posteriors_mcpdf.begin();
257 cout <<
"MAIN: Starting estimation" << endl;
258 unsigned int time_step;
259 for (time_step = 0; time_step < num_timesteps; time_step++)
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;
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;
286 mobile_robot.
Move(input);
288 if ((time_step+1)%5 == 0){
290 ColumnVector measurement = mobile_robot.
Measure();
292 filter->
Update(&sys_model,input,&meas_model,measurement);
295 filter->
Update(&sys_model,input);
300 switch (smoother_name){
302 *posteriors_it_gauss = *(
Gaussian*)(posterior);
303 posteriors_it_gauss++;
307 posteriors_it_mcpdf++;
310 cout <<
"Type if filter not recognised on construction" <<endl;
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;
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;
340 cout <<
"After " << time_step+1 <<
" timesteps " << endl;
341 cout <<
" Posterior Mean = " << endl << posterior->
ExpectedValueGet() << endl
342 <<
" Covariance = " << endl << posterior->
CovarianceGet() <<
"" << endl;
345 cout <<
"======================================================" << endl
346 <<
"End of the filter for mobile robot localisation" << endl
347 <<
"======================================================" 356 switch (smoother_name){
358 cout <<
"Using the RauchTungStriebelSmoother" << endl;
362 cout <<
"Using the particlesmoother, " << NUM_SAMPLES <<
" samples" << endl;
366 cout <<
"Type if filter not recognised on construction" <<endl;
369 fout_time_smooth << time_step <<
";" << endl;
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;
390 cout <<
"======================================================" << endl
391 <<
"Start of the smoother for mobile robot localisation" << endl
392 <<
"======================================================" 394 for (time_step = num_timesteps-1; time_step+1 > 0 ; time_step--)
397 switch (smoother_name){
399 posteriors_it_gauss--;
400 Gaussian filtered = *posteriors_it_gauss;
401 backwardfilter->
Update(&sys_model,input, &filtered);
404 posteriors_it_mcpdf--;
406 cout <<
"before update" << endl;
407 backwardfilter->
Update(&sys_model,input, &filtered);
408 cout <<
"after update" << endl;
411 cout <<
"Type if filter not recognised on construction" <<endl;
417 fout_time_smooth << time_step <<
";" << endl;
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;
437 switch (smoother_name){
439 *posteriors_it_gauss = *(
Gaussian*)(posterior);
445 cout <<
"Type if filter not recognised on construction" <<endl;
454 delete backwardfilter;
456 cout <<
"======================================================" << endl
457 <<
"End of the backward filter for mobile robot localisation" << endl
458 <<
"======================================================" 469 fout_time_smooth.close();
470 fout_E_smooth.close();
471 fout_cov_smooth.close();
474 fout_particles.close();
475 fout_numparticles.close();
476 fout_particles_smooth.close();
477 fout_numparticles_smooth.close();
virtual MatrixWrapper::SymmetricMatrix CovarianceGet() const
Get the Covariance Matrix E[(x - E[x])^2] of the Analytic pdf.
MatrixWrapper::ColumnVector GetState()
Particular particle filter : Proposal PDF = SystemPDF.
virtual MatrixWrapper::ColumnVector ExpectedValueGet() const
Get the expected value E[x] of the pdf.
Class PDF: Virtual Base class representing Probability Density Functions.
This is a class simulating a mobile robot.
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)
Virtual Baseclass representing all bayesian backward filters.
virtual Pdf< StateVar > * PostGet()
Get Posterior density.
virtual Pdf< StateVar > * PostGet()
Get Posterior density.
Non Linear Conditional Gaussian.
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.
Class for analytic system models with additive Gauss. uncertainty.
Class for linear analytic measurementmodels with additive gaussian noise.
Linear Conditional Gaussian.
const unsigned int NUM_SAMPLES
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)
bool ListOfSamplesSet(const vector< WeightedSample< T > > &list_of_samples)
Set the list of weighted samples.