48 double epsilon_large = 0.5;
49 double epsilon_huge = 2.0;
67 Gaussian System_Uncertainty(SysNoise_Mu, SysNoise_Cov);
76 double wall_ct = 2/(sqrt(pow(
RICO_WALL,2.0) + 1));
88 Gaussian Measurement_Uncertainty(MeasNoise_Mu,MeasNoise_Cov);
105 Gaussian prior_cont(prior_mu,prior_sigma);
108 vector<Sample<ColumnVector> > prior_samples(
NUM_SAMPLES);
123 Gaussian prior_cont1(prior_mu1,prior_sigma1);
138 Gaussian prior_cont2(prior_mu2,prior_sigma2);
153 Gaussian prior_cont3(prior_mu3,prior_sigma3);
168 Gaussian prior_cont4(prior_mu4,prior_sigma4);
174 vector<Pdf<ColumnVector>*> mixVec(3);
175 mixVec[0] = &mixcomp1;
176 mixVec[1] = &mixcomp2;
177 mixVec[2] = &mixcomp3;
185 cov_check(1,1) =
PRIOR_COV_X; cov_check(1,2) = 0; cov_check(1,3) = 0;
186 cov_check(2,1) = 0; cov_check(2,2) =
PRIOR_COV_Y; cov_check(2,3) = 0;
187 cov_check(3,1) = 0; cov_check(3,2) = 0; cov_check(3,3) =
PRIOR_COV_THETA;
206 Filter<ColumnVector,ColumnVector> *my_filter_extendedkalman, *my_filter_iteratedextendedkalman, *my_filter_bootstrap, *my_filter_ekparticle, *my_filter_mixtureBootstrap;
216 ColumnVector measurement ;
217 ColumnVector mobile_robot_state ;
219 ofstream mixtureFile;
222 mixtureFile.open(
"mixtureOutput.txt");
225 cout <<
"Running 4 different filters. This may take a few minutes... " << endl;
226 unsigned int time_step;
230 mobile_robot.
Move(input);
233 measurement = mobile_robot.
Measure();
234 mobile_robot_state = mobile_robot.
GetState();
238 posterior_mixtureBootstrap = my_filter_mixtureBootstrap->
PostGet();
239 vector<WeightedSample<ColumnVector> > los;
240 vector<WeightedSample<ColumnVector> >::iterator los_it;
242 mixtureFile << time_step <<
" " << numComp <<
" ";
243 mixtureFile << mobile_robot_state(1) <<
" " << mobile_robot_state(2) <<
" " << mobile_robot_state(3) <<
" ";
244 for(
int i = 0 ; i<numComp ; i++ )
246 double componentWeight = (
dynamic_cast<Mixture<ColumnVector> *
>(posterior_mixtureBootstrap)->WeightGet(i)) ;
248 mixtureFile << i <<
" " << componentWeight <<
" " << los.size()<<
" " <<
STATE_SIZE <<
" ";
249 for ( los_it=los.begin(); los_it != los.end() ; los_it++)
252 mixtureFile << los_it->ValueGet()[j] <<
" ";
253 mixtureFile<< los_it->WeightGet() <<
" ";
259 my_filter_extendedkalman->
Update(&sys_model,input,&meas_model, measurement);
260 my_filter_iteratedextendedkalman->
Update(&sys_model,input,&meas_model, measurement);
261 my_filter_bootstrap->
Update(&sys_model,input,&meas_model, measurement);
263 my_filter_mixtureBootstrap->
Update(&sys_model,input,&meas_model, measurement);
268 posterior_mixtureBootstrap = my_filter_mixtureBootstrap->
PostGet();
269 vector<WeightedSample<ColumnVector> > los;
270 vector<WeightedSample<ColumnVector> >::iterator los_it;
272 mixtureFile << time_step <<
" " << numComp <<
" ";
273 mixtureFile << mobile_robot_state(1) <<
" " << mobile_robot_state(2) <<
" " << mobile_robot_state(3) <<
" ";
274 for(
int i = 0 ; i<numComp ; i++ )
276 double componentWeight = (
dynamic_cast<Mixture<ColumnVector> *
>(posterior_mixtureBootstrap)->WeightGet(i)) ;
278 mixtureFile << i <<
" " << componentWeight <<
" " << los.size()<<
" " <<
STATE_SIZE <<
" ";
279 for ( los_it=los.begin(); los_it != los.end() ; los_it++)
282 mixtureFile << los_it->ValueGet()[j] <<
" ";
283 mixtureFile<< los_it->WeightGet() <<
" ";
293 mean_ek_check=mobile_robot.
GetState();
296 cov_ek_check(1,1) = 0.0599729; cov_ek_check(1,2) = 0.000291386; cov_ek_check(1,3) = 0.00223255;
297 cov_ek_check(2,1) = 0.000291386; cov_ek_check(2,2) = 0.000277528; cov_ek_check(2,3) = 0.000644136;
298 cov_ek_check(3,1) = 0.00223255; cov_ek_check(3,2) = 0.000644136; cov_ek_check(3,3) = 0.00766009;
305 mean_it_check=mobile_robot.
GetState();
309 cov_it_check(1,1) = 0.0611143; cov_it_check(1,2) = 0.000315923; cov_it_check(1,3) = 0.00238938;
310 cov_it_check(2,1) = 0.000315923; cov_it_check(2,2) = 0.000280736; cov_it_check(2,3) = 0.000665735;
311 cov_it_check(3,1) = 0.00238938; cov_it_check(3,2) = 0.000665735; cov_it_check(3,3) = 0.00775776;
318 mean_bs_check=mobile_robot.
GetState();
344 posterior_mixtureBootstrap = my_filter_mixtureBootstrap->
PostGet();
347 mean_mbs_check(1) = mobile_robot_state(1); mean_mbs_check(2) = mobile_robot_state(2); mean_mbs_check(3) = mobile_robot_state(3);
349 vector<Probability> weights=
dynamic_cast<Mixture<ColumnVector> *
>(posterior_mixtureBootstrap)->WeightsGet();
351 for(
int i = 0 ; i< dynamic_cast<Mixture<ColumnVector> *>(posterior_mixtureBootstrap)->NumComponentsGet(); i++ )
368 delete my_filter_extendedkalman;
369 delete my_filter_iteratedextendedkalman;
370 delete my_filter_bootstrap;
371 delete my_filter_ekparticle;
372 delete my_filter_mixtureBootstrap;
379 int num_cond_args = 1;
383 int cond_arg_dims[num_cond_args];
384 cond_arg_dims[0] = num_states;
386 std::vector<int> cond_args(num_cond_args);
387 double prob_diag = 0.9;
388 double prob_nondiag = (1-prob_diag)/(num_states-1);
389 for (
int state_kMinusOne = 0 ; state_kMinusOne < num_states ; state_kMinusOne++)
391 cond_args[0] = state_kMinusOne;
392 for (
int state_k = 0 ; state_k < num_states ; state_k++)
394 if (state_kMinusOne == state_k) sys_pdf.
ProbabilitySet(prob_diag,state_k,cond_args);
408 SymmetricMatrix measNoise_Cov(
MEAS_SIZE);
410 Gaussian measurement_uncertainty(measNoise_Mu, measNoise_Cov);
433 ColumnVector input(2);
441 unsigned int time_step;
445 mobile_robot.
Move(input);
447 ColumnVector measurement = mobile_robot.
Measure();
449 measurement(1) = 0-measurement(1);
451 filter.
Update(&sys_model,&meas_model,measurement);
455 for (
int state=0; state< num_states; state++)
MatrixWrapper::ColumnVector GetState()
Class representing a PDF on a discrete variable.
Particular particle filter : Proposal PDF = SystemPDF.
Class PDF: Virtual Base class representing Probability Density Functions.
Class representing the histogram filter.
This is a class simulating a mobile robot.
MatrixWrapper::ColumnVector Measure()
virtual T ExpectedValueGet() const
Get the expected value E[x] of the pdf.
Class representing Gaussian (or normal density)
#define MU_SYSTEM_NOISE_X
void testComplete_FilterValue_Cont()
Particular mixture particle filter : Proposal PDF = SystemPDF.
Particle filter using EKF for proposal step.
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
#define MU_SYSTEM_NOISE_THETA
#define RESAMPLE_THRESHOLD
#define SIGMA_SYSTEM_NOISE_THETA
virtual Pdf< StateVar > * PostGet()
Get Posterior density.
Non Linear Conditional Gaussian.
Class representing a mixture of PDFs, the mixture can contain different.
virtual DiscretePdf * PostGet()
Get Posterior density.
void Move(MatrixWrapper::ColumnVector inputs)
Monte Carlo Pdf: Sample based implementation of Pdf.
Class for analytic system models with additive Gauss. uncertainty.
void ProbabilitySet(const double &prob, const int &input, const std::vector< int > &condargs) const
Set the probability (Typical for discrete Pdf's)
Abstract Class representing all FULLY Discrete Conditional PDF's.
Class for linear analytic measurementmodels with additive gaussian noise.
Linear Conditional Gaussian.
Class for discrete System Models.
void testComplete_FilterValue_Discr()
Probability ProbabilityGet(const int &state) const
Implementation of virtual base class method.
#define SIGMA_SYSTEM_NOISE_X
const unsigned int NUM_SAMPLES
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)
T ExpectedValueGet() const
Get the expected value E[x] of the pdf.
bool approxEqual(double a, double b, double epsilon)
virtual MatrixWrapper::ColumnVector ExpectedValueGet() const
Get the expected value E[x] of the pdf.
bool ListOfSamplesSet(const vector< WeightedSample< T > > &list_of_samples)
Set the list of weighted samples.
#define MU_SYSTEM_NOISE_Y
CPPUNIT_TEST_SUITE_REGISTRATION(Complete_FilterTest)
#define SIGMA_SYSTEM_NOISE_Y