31 #include "../mobile_robot.h" 37 #include "../mobile_robot_wall_cts.h" 72 int main(
int argc,
char** argv)
74 cerr <<
"==================================================" << endl
75 <<
"Test of bootstrap filter" << endl
76 <<
"Mobile robot localisation example" << endl
77 <<
"==================================================" << endl;
93 sys_noise_Cov(1,2) = 0.0;
94 sys_noise_Cov(1,3) = 0.0;
95 sys_noise_Cov(2,1) = 0.0;
97 sys_noise_Cov(2,3) = 0.0;
98 sys_noise_Cov(3,1) = 0.0;
99 sys_noise_Cov(3,2) = 0.0;
102 Gaussian system_Uncertainty(sys_noise_Mu, sys_noise_Cov);
114 double wall_ct = 2/(sqrt(pow(
RICO_WALL,2.0) + 1));
118 H(1,2) = 0 - wall_ct;
123 SymmetricMatrix meas_noise_Cov(
MEAS_SIZE);
125 Gaussian measurement_Uncertainty(meas_noise_Mu, meas_noise_Cov);
141 prior_Cov(1,2) = 0.0;
142 prior_Cov(1,3) = 0.0;
143 prior_Cov(2,1) = 0.0;
145 prior_Cov(2,3) = 0.0;
146 prior_Cov(3,1) = 0.0;
147 prior_Cov(3,2) = 0.0;
149 Gaussian prior_cont(prior_Mu,prior_Cov);
152 vector<Sample<ColumnVector> > prior_samples(
NUM_SAMPLES);
168 ColumnVector input(2);
178 cout <<
"MAIN: Starting estimation" << endl;
179 unsigned int time_step;
183 mobile_robot.
Move(input);
186 ColumnVector measurement = mobile_robot.
Measure();
189 filter.
Update(&sys_model,input,&meas_model,measurement);
196 cout <<
"After " << time_step+1 <<
" timesteps " << endl;
197 cout <<
" Posterior Mean = " << endl << posterior->
ExpectedValueGet() << endl
198 <<
" Covariance = " << endl << posterior->
CovarianceGet() <<
"" << endl;
201 cout <<
"======================================================" << endl
202 <<
"End of the Bootstrap filter for mobile robot localisation" << endl
203 <<
"======================================================"
Particular particle filter : Proposal PDF = SystemPDF.
Class PDF: Virtual Base class representing Probability Density Functions.
This is a class simulating a mobile robot.
virtual MCPdf< StateVar > * PostGet()
Get Posterior density.
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()
Non Linear Conditional Gaussian.
Class representing Gaussian (or normal density)
#define MU_SYSTEM_NOISE_X
#define MU_SYSTEM_NOISE_THETA
#define SIGMA_SYSTEM_NOISE_THETA
int main(int argc, char **argv)
virtual T ExpectedValueGet() const
Get the expected value E[x] of the pdf.
void Move(MatrixWrapper::ColumnVector inputs)
Monte Carlo Pdf: Sample based implementation of Pdf.
Class for linear analytic measurementmodels with additive gaussian noise.
Linear Conditional Gaussian.
#define SIGMA_SYSTEM_NOISE_X
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.
#define MU_SYSTEM_NOISE_Y
#define SIGMA_SYSTEM_NOISE_Y