29 #include "../examples/mobile_robot_wall_cts.h"    30 #include "../examples/mobile_robot.h"    51   double epsilon_large = 0.5;
    52   double epsilon_huge  = 2.0;
    95       Gaussian System_Uncertainty(SysNoise_Mu, SysNoise_Cov);
   103       double wall_ct = 2/(sqrt(pow(
RICO_WALL,2.0) + 1));
   107       H(1,2) = 0 - wall_ct;
   111       SymmetricMatrix MeasNoise_Cov(
MEAS_SIZE);
   115       Gaussian Measurement_Uncertainty(MeasNoise_Mu,MeasNoise_Cov);
   132       Gaussian prior_cont(prior_mu,prior_sigma);
   146       ColumnVector input(2);
   154       vector<Gaussian>::iterator posteriors_it  = posteriors.begin();
   159       unsigned int time_step;
   167           mobile_robot.
Move(input);
   169           if ((time_step+1)%10 == 0){
   171             ColumnVector measurement = mobile_robot.
Measure();
   174             filter.
Update(&sys_model,input,&meas_model,measurement);
   177             filter.
Update(&sys_model,input);
   181           *posteriors_it = *posterior;
   199       for (time_step = NUM_TIME_STEPS-1; time_step+1 > 0 ; time_step--)
   203           Gaussian filtered(posteriors_it->ExpectedValueGet(),posteriors_it->CovarianceGet());
   204           backwardfilter.
Update(&sys_model,input, &filtered);
   215   SymmetricMatrix cov_smoother_check(
STATE_SIZE);
   216   cov_smoother_check=0.0;
   218   CPPUNIT_ASSERT_EQUAL(
approxEqual(posteriors_it->ExpectedValueGet(), mean_smoother_check, epsilon_large),
true);
   219   CPPUNIT_ASSERT_EQUAL(
approxEqual(posteriors_it->CovarianceGet(), cov_smoother_check, epsilon_large),
true);
 
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
void testKalmanSmoother()
#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. 
void testParticleSmoother()
Class for linear analytic measurementmodels with additive gaussian noise. 
Linear Conditional Gaussian. 
CPPUNIT_TEST_SUITE_REGISTRATION(SmootherTest)
#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) 
bool approxEqual(double a, double b, double epsilon)
#define MU_SYSTEM_NOISE_Y
#define SIGMA_SYSTEM_NOISE_Y