test_nonlinear_kalman.cpp
Go to the documentation of this file.
1 // $Id: kalman_mobile.cpp 5925 2006-03-14 21:23:49Z tdelaet $
2 // Copyright (C) 2006 Tinne De Laet <first dot last at mech dot kuleuven dot be>
3 //
4 // This program is free software; you can redistribute it and/or modify
5 // it under the terms of the GNU Lesser General Public License as published by
6 // the Free Software Foundation; either version 2.1 of the License, or
7 // (at your option) any later version.
8 //
9 // This program is distributed in the hope that it will be useful,
10 // but WITHOUT ANY WARRANTY; without even the implied warranty of
11 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 // GNU Lesser General Public License for more details.
13 //
14 // You should have received a copy of the GNU Lesser General Public License
15 // along with this program; if not, write to the Free Software
16 // Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA.
17 
18 /* Demonstration program for the Bayesian Filtering Library.
19  Mobile robot localization with respect to wall with different possibilities for filter
20 */
21 
22 
24 
27 
30 #include "../nonlinearanalyticconditionalgaussianmobile.h"//added
31 
32 #include "../mobile_robot.h"
33 
34 #include <iostream>
35 #include <fstream>
36 
37 // Include file with properties
38 #include "../mobile_robot_wall_cts.h"
39 
40 using namespace MatrixWrapper;
41 using namespace BFL;
42 using namespace std;
43 
44 
45 
46 /* The purpose of this program is to construct a kalman filter for the problem
47  of localisation of a mobile robot equipped with an ultrasonic sensor.
48  In this case the orientation is known, which simplifies the model considerably:
49  The system model will become linear.
50  The ultrasonic measures the distance to the wall (it can be switched off:
51  see mobile_robot_wall_cts.h)
52 
53  The necessary SYSTEM MODEL is:
54 
55  x_k = x_{k-1} + v_{k-1} * cos(theta) * delta_t
56  y_k = y_{k-1} + v_{k-1} * sin(theta) * delta_t
57 
58  The used MEASUREMENT MODEL:
59  measuring the (perpendicular) distance z to the wall y = ax + b
60 
61  set WALL_CT = 1/sqrt(pow(a,2) + 1)
62  z = WALL_CT * a * x - WALL_CT * y + WALL_CT * b + GAUSSIAN_NOISE
63  or Z = H * X_k + J * U_k
64 
65  where
66 
67  H = [ WALL_CT * a - WALL_CT 0 ]
68  and GAUSSIAN_NOISE = N((WALL_CT * b), SIGMA_MEAS_NOISE)
69 
70 */
71 
72 
73 int main(int argc, char** argv)
74 {
75  cerr << "==================================================" << endl
76  << "Test of kalman filter" << endl
77  << "Mobile robot localisation example" << endl
78  << "==================================================" << endl;
79 
80 
81  /****************************
82  * NonLinear system model *
83  ***************************/
84 
85  // create gaussian
86  ColumnVector sys_noise_Mu(STATE_SIZE);
87  sys_noise_Mu(1) = MU_SYSTEM_NOISE_X;
88  sys_noise_Mu(2) = MU_SYSTEM_NOISE_Y;
89  sys_noise_Mu(3) = MU_SYSTEM_NOISE_THETA;
90 
91  SymmetricMatrix sys_noise_Cov(STATE_SIZE);
92  sys_noise_Cov = 0.0;
93  sys_noise_Cov(1,1) = SIGMA_SYSTEM_NOISE_X;
94  sys_noise_Cov(1,2) = 0.0;
95  sys_noise_Cov(1,3) = 0.0;
96  sys_noise_Cov(2,1) = 0.0;
97  sys_noise_Cov(2,2) = SIGMA_SYSTEM_NOISE_Y;
98  sys_noise_Cov(2,3) = 0.0;
99  sys_noise_Cov(3,1) = 0.0;
100  sys_noise_Cov(3,2) = 0.0;
101  sys_noise_Cov(3,3) = SIGMA_SYSTEM_NOISE_THETA;
102 
103  Gaussian system_Uncertainty(sys_noise_Mu, sys_noise_Cov);
104 
105  // create the model
106  NonLinearAnalyticConditionalGaussianMobile sys_pdf(system_Uncertainty);
107  AnalyticSystemModelGaussianUncertainty sys_model(&sys_pdf);
108 
109  /*********************************
110  * Initialise measurement model *
111  ********************************/
112 
113  // create matrix H for linear measurement model
114  double wall_ct = 2/(sqrt(pow(RICO_WALL,2.0) + 1));
115  Matrix H(MEAS_SIZE,STATE_SIZE);
116  H = 0.0;
117  H(1,1) = wall_ct * RICO_WALL;
118  H(1,2) = 0 - wall_ct;
119  H(1,3) = 0.0;
120  // Construct the measurement noise (a scalar in this case)
121  ColumnVector meas_noise_Mu(MEAS_SIZE);
122  meas_noise_Mu(1) = MU_MEAS_NOISE;
123 
124  SymmetricMatrix meas_noise_Cov(MEAS_SIZE);
125  meas_noise_Cov(1,1) = SIGMA_MEAS_NOISE;
126  Gaussian measurement_Uncertainty(meas_noise_Mu, meas_noise_Cov);
127 
128  // create the measurement model
129  LinearAnalyticConditionalGaussian meas_pdf(H, measurement_Uncertainty);
131 
132  /****************************
133  * Linear prior DENSITY *
134  ***************************/
135  // Continuous Gaussian prior (for Kalman filters)
136  ColumnVector prior_Mu(STATE_SIZE);
137  prior_Mu(1) = PRIOR_MU_X;
138  prior_Mu(2) = PRIOR_MU_Y;
139  prior_Mu(3) = PRIOR_MU_THETA;
140  SymmetricMatrix prior_Cov(STATE_SIZE);
141  prior_Cov(1,1) = PRIOR_COV_X;
142  prior_Cov(1,2) = 0.0;
143  prior_Cov(1,3) = 0.0;
144  prior_Cov(2,1) = 0.0;
145  prior_Cov(2,2) = PRIOR_COV_Y;
146  prior_Cov(2,3) = 0.0;
147  prior_Cov(3,1) = 0.0;
148  prior_Cov(3,2) = 0.0;
149  prior_Cov(3,3) = PRIOR_COV_THETA;
150  Gaussian prior_cont(prior_Mu,prior_Cov);
151 
152  /******************************
153  * Construction of the Filter *
154  ******************************/
155  ExtendedKalmanFilter filter(&prior_cont);
156 
157  /***************************
158  * initialise MOBILE ROBOT *
159  **************************/
160  // Model of mobile robot in world with one wall
161  // The model is used to simultate the distance measurements.
162  MobileRobot mobile_robot;
163  ColumnVector input(2);
164  input(1) = 0.1;
165  input(2) = 0.0;
166 
167 
168 
169 
170  /*******************
171  * ESTIMATION LOOP *
172  *******************/
173  cout << "MAIN: Starting estimation" << endl;
174  unsigned int time_step;
175  for (time_step = 0; time_step < NUM_TIME_STEPS-1; time_step++)
176  {
177  // DO ONE STEP WITH MOBILE ROBOT
178  mobile_robot.Move(input);
179 
180  // DO ONE MEASUREMENT
181  ColumnVector measurement = mobile_robot.Measure();
182 
183  // UPDATE FILTER
184  filter.Update(&sys_model,input,&meas_model,measurement);
185  //filter.Update(&sys_model,input);
186 
187  } // estimation loop
188 
189 
190 
191  Pdf<ColumnVector> * posterior = filter.PostGet();
192  cout << "After " << time_step+1 << " timesteps " << endl;
193  cout << " Posterior Mean = " << endl << posterior->ExpectedValueGet() << endl
194  << " Covariance = " << endl << posterior->CovarianceGet() << "" << endl;
195 
196 
197  cout << "======================================================" << endl
198  << "End of the Kalman filter for mobile robot localisation" << endl
199  << "======================================================"
200  << endl;
201 
202 
203  return 0;
204 }
#define MU_MEAS_NOISE
#define SIGMA_MEAS_NOISE
Class PDF: Virtual Base class representing Probability Density Functions.
Definition: pdf.h:53
This is a class simulating a mobile robot.
Definition: mobile_robot.h:47
MatrixWrapper::ColumnVector Measure()
#define MEAS_SIZE
virtual T ExpectedValueGet() const
Get the expected value E[x] of the pdf.
Class representing Gaussian (or normal density)
Definition: gaussian.h:27
#define MU_SYSTEM_NOISE_X
#define RICO_WALL
#define MU_SYSTEM_NOISE_THETA
#define SIGMA_SYSTEM_NOISE_THETA
#define STATE_SIZE
#define PRIOR_COV_THETA
#define PRIOR_COV_Y
void Move(MatrixWrapper::ColumnVector inputs)
Class for analytic system models with additive Gauss. uncertainty.
#define PRIOR_MU_X
virtual Gaussian * PostGet()
Get Posterior density.
#define PRIOR_MU_THETA
#define PRIOR_COV_X
Class for linear analytic measurementmodels with additive gaussian noise.
#define SIGMA_SYSTEM_NOISE_X
#define PRIOR_MU_Y
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)
Definition: filter.h:56
#define MU_SYSTEM_NOISE_Y
#define SIGMA_SYSTEM_NOISE_Y
#define NUM_TIME_STEPS
int main(int argc, char **argv)


bfl
Author(s): Klaas Gadeyne, Wim Meeussen, Tinne Delaet and many others. See web page for a full contributor list. ROS package maintained by Wim Meeussen.
autogenerated on Mon Feb 28 2022 21:56:33