32 #include "../compare_filters/nonlinearanalyticconditionalgaussianmobile.h" 33 #include "../mobile_robot.h" 42 #include "../examples/mobile_robot_wall_cts.h" 75 int main(
int argc,
char** argv)
77 cerr <<
"==================================================" << endl
78 <<
"Test of different smooters" << endl
79 <<
"Mobile robot localisation example" << endl
80 <<
"==================================================" << endl;
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;
87 fout_time.open(
"time.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");
110 sys_noise_Cov(1,2) = 0.0;
111 sys_noise_Cov(1,3) = 0.0;
112 sys_noise_Cov(2,1) = 0.0;
114 sys_noise_Cov(2,3) = 0.0;
115 sys_noise_Cov(3,1) = 0.0;
116 sys_noise_Cov(3,2) = 0.0;
119 Gaussian system_Uncertainty(sys_noise_Mu, sys_noise_Cov);
129 double wall_ct = 2/(sqrt(pow(
RICO_WALL,2.0) + 1));
133 H(1,2) = 0 - wall_ct;
137 SymmetricMatrix MeasNoise_Cov(
MEAS_SIZE);
141 Gaussian measurement_Uncertainty(MeasNoise_Mu,MeasNoise_Cov);
160 Gaussian prior_cont(prior_mu,prior_sigma);
163 cout<<
"Prior initialised"<<
"" << endl;
165 <<
"Covariance = " << endl << prior_cont.
CovarianceGet() << endl;
180 ColumnVector input(2);
188 vector<Gaussian>::iterator posteriors_it = posteriors.begin();
193 cout <<
"MAIN: Starting estimation" << endl;
194 unsigned int time_step;
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;
212 mobile_robot.
Move(input);
214 if ((time_step+1)%10 == 0){
216 ColumnVector measurement = mobile_robot.
Measure();
219 filter.
Update(&sys_model,input,&meas_model,measurement);
222 filter.
Update(&sys_model,input);
227 *posteriors_it = *posterior;
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;
247 cout <<
"After " << time_step+1 <<
" timesteps " << endl;
248 cout <<
" Posterior Mean = " << endl << posterior->
ExpectedValueGet() << endl
249 <<
" Covariance = " << endl << posterior->
CovarianceGet() <<
"" << endl;
252 cout <<
"======================================================" << endl
253 <<
"End of the filter for mobile robot localisation" << endl
254 <<
"======================================================" 263 fout_time_smooth << time_step <<
";" << endl;
274 cout <<
"======================================================" << endl
275 <<
"Start of the smoother for mobile robot localisation" << endl
276 <<
"======================================================" 278 for (time_step = NUM_TIME_STEPS-1; time_step+1 > 0 ; time_step--)
282 Gaussian filtered(posteriors_it->ExpectedValueGet(),posteriors_it->CovarianceGet());
283 backwardfilter.
Update(&sys_model,input, &filtered);
286 fout_time_smooth << time_step <<
";" << endl;
300 cout <<
"After Smoothing first timestep " << endl;
301 cout <<
" Posterior Mean = " << endl << posteriors_it->ExpectedValueGet() << endl
302 <<
" Covariance = " << endl << posteriors_it->CovarianceGet() <<
"" << endl;
306 cout <<
"======================================================" << endl
307 <<
"End of the Kalman smoother for mobile robot localisation" << endl
308 <<
"======================================================" 320 fout_time_smooth.close();
321 fout_E_smooth.close();
322 fout_cov_smooth.close();
MatrixWrapper::ColumnVector GetState()
Class PDF: Virtual Base class representing Probability Density Functions.
This is a class simulating a mobile robot.
MatrixWrapper::ColumnVector Measure()
Class representing all Rauch-Tung-Striebel backward filters.
virtual T ExpectedValueGet() const
Get the expected value E[x] of the pdf.
Class representing Gaussian (or normal density)
virtual Pdf< StateVar > * PostGet()
Get Posterior density.
#define MU_SYSTEM_NOISE_X
int main(int argc, char **argv)
virtual MatrixWrapper::SymmetricMatrix CovarianceGet() const
Get the Covariance Matrix E[(x - E[x])^2] of the Analytic pdf.
#define MU_SYSTEM_NOISE_THETA
#define SIGMA_SYSTEM_NOISE_THETA
Non Linear Conditional Gaussian.
virtual bool Update(SystemModel< StateVar > *const sysmodel, const StateVar &u, Pdf< StateVar > *const filtered_post)
Full Update (system with inputs)
void Move(MatrixWrapper::ColumnVector inputs)
Class for analytic system models with additive Gauss. uncertainty.
virtual Gaussian * PostGet()
Get Posterior density.
Class for linear analytic measurementmodels with additive gaussian noise.
Linear Conditional Gaussian.
#define SIGMA_SYSTEM_NOISE_X
virtual MatrixWrapper::SymmetricMatrix CovarianceGet() const
Get the Covariance Matrix E[(x - E[x])^2] of the Analytic pdf.
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)
virtual MatrixWrapper::ColumnVector ExpectedValueGet() const
Get the expected value E[x] of the pdf.
#define MU_SYSTEM_NOISE_Y
#define SIGMA_SYSTEM_NOISE_Y