-
Notifications
You must be signed in to change notification settings - Fork 54
/
Copy pathMain.m
284 lines (243 loc) · 9.41 KB
/
Main.m
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%
% RAO BLACKWELLIZED PARTICLE FILTER FOR GRID-BASED FAST SALM SIMULATOR
%
% Based on 'Probabilistic Robotics' by Thrun, Burgard and Fox and several
% papers by Cyril Stachniss
%
% Adrian Llopart Maurin 15.04.16
% PhD in the AUT Group at the Technical University of Denmark
% adllo@elektro.dtu.dk
%
%
% DESCRIPTION
% Simulation of a robot moving through a determined path in a predefined map and the
% resulting occupancy grid of a particle filter which only takes the control commands
% and true laser scans as inputs
%
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Clean up
clear variables
close all
clc
addpath(genpath('rvctools'))
rng(1) % Adjust the noise realization here
%% Simulation Parameters
% General parameters
Ts = 1; % Sampling time
n_cell=10; % Number of cells per meter
NPC = 3; % Number of particles used
usable_area = 4*n_cell; % Use laser data in 4 meter radius
sigma_v = [0.01 0.01]; % Standard deviation of sensor (Holds for up to 20m) (m)
R1 = [0.1 0;0 0.001]; % Variance matrix for odometry
Nsamples = 10; % Number of samples for Particle Filter
max_speed=4; % max_speen*n_cell cm/timestep
% LRS_Sensor Structure
LRS.MaxDistance = 80*n_cell; % Maximum sensor measurement distance (m/10)
LRS.Resolution = 0.5; % Sensor resolution (degrees)
LRS.FoV = 180; % Sensor field of view (degrees)
LRS.MaxAngle = 1.5773; % extreme angle of laser scanner
%% Map Generation
%Consists of (x,y) start and end points that define a line in the space
map = zeros(4,24);
%Wall Exterior
map(:,1) = [80; 20; 210; 20];
map(:,2) = [210; 20; 210; 230];
map(:,3) = [210; 230; 80; 230];
map(:,4) = [80; 230; 80; 170];
map(:,5) = [80; 170; 20; 170];
map(:,6) = [20; 170; 20; 80];
map(:,7) = [20; 80; 80; 80];
map(:,8) = [80; 80; 80; 20];
%Wall Interior
map(:,9) = [110; 50; 180; 50];
map(:,10) = [180; 50; 180; 200];
map(:,11) = [180; 200; 110; 200];
map(:,12) = [110; 200; 110; 170];
map(:,13) = [110; 170; 170; 170];
map(:,14) = [170; 170; 170; 80];
map(:,15) = [170; 80; 110; 80];
map(:,16) = [110; 80; 110; 50];
%Wall Interior
map(:,17) = [50; 110; 140; 110];
map(:,18) = [140; 110; 140; 140];
map(:,19) = [140; 140; 50; 140];
map(:,20) = [50; 140; 50; 110];
% % Plot map
% figure(1)
% clf
% hold on
% for d = 1:size(map,2)
% plot([map(1,d) map(3,d)],[map(2,d) map(4,d)],'k')
% end
%
% % First Path Generation
% via = [105,35; 185,35; 185,40; 190,45; 195,50; 195,203; 190,207; 185,210; 180,215; 105,215; 103,195; 100,190; 95,185; ...
% 95,170; 100,165; 105,160; 110,155; 140,155; 145,150; 150,145; 155,140; 155,110; 150,105; 145,100; 140,95; 50,95; ...
% 45,100: 40,105; 35,110; 35,140; 40,145; 45,150; 50,155; 110,155; 140,155; 145,150; 150,145; 155,140; 155,110; ...
% 150,105; 145,100; 140,95; 110,95; 105,90; 100,85; 95,80;95,35];
% %Controller Parameters
% d = 1;
% Kp = 0.15;
% Kh = 0.5;
%% Second path generation
via = [100,35; 185,35; 185,40; 190,45; 195,50; 195,200; 190,205; 185,210; 180,215; 110,215; 105,195; 100,190; 95,185; ...
95,170; 90,165; 85,160; 80, 155; 50,155; 45, 150; 40,145; 35,140; 35,110; 40,105; 45, 100; 50,95; 140,95; 145,100; ...
150,105; 155,110; 155,140; 150,145; 145,150; 140,155; 50,155; 45, 150; 30,145; 35,140; 35,110; 40,105; ...
45,100; 50,95; 80,95; 85,90; 90,85; 95,80; 95,35];
%Controller Parameters
d = 1;
Kp = 0.4;
Kh = 0.9;
%% Generation of a high order polynomial with the drive-through
% points and a desired velocity as boundary conditions.
path = mstraj(via,[max_speed, max_speed],[],[via(1,1) via(1,2)],Ts,0);
switch max_speed %Calculated Model Velocity parameters (a) via Motion_Model_Velocity_Test
case 2
a= [0.05 0.01 0.01 0.05 0.0001 0.0001];
case 3
a= [0.1 0.001 0.001 0.1 0.0001 0.0001];
case 4
a=[0.1 0.01 0.01 0.1 0.0001 0.0001];
case 5
a=[0.1 0.001 0.001 0.1 0.0001 0.0001];
end
%% Grid occupancy initialisation
Nstep=size(path,1);
security=1.2; % Initialise the grid 120% bigger than the map actually is
xg=max(max(map))*security; % Length
yg=xg; % Width
L=0.5*ones(yg,xg); % Initialise the probability of grid map
%% Data Initialization
%Allocating sufficient space for the variables.
Nsim = size(path,1);
u = zeros(2,Nsim);
x = zeros(3,Nsim);
x0 = [via(1,1),via(1,2),0]; % Initialize robot pose at the start of the path.
%Particle Filter Structure
pf.k = 1; % Iteration number
pf.NPC = NPC; % Number of particles
pf.q = zeros(pf.NPC, Nsim); % Weights
pf.particles = zeros(3, pf.NPC, Nsim); % Particles position
pf.sigma_v = sigma_v; % Propagating the noise of the sensor
pf.P = zeros(yg, xg, pf.NPC); % Actual probability of grid map
pf.L = zeros(yg, xg, pf.NPC); % Log odds probability
pf.L0 = 0; % L0 value for inverse_range_sensor_model
pf.gridsize = [xg yg]; % Gridsize
pf.xh = zeros(3, Nsim); % Estiamte of true position
pf.R1 = R1; % Variance matrix for odometry
pf.UsableArea = usable_area; % Laser scanner usable area
%% Time step = 1 initialization
tic
h = timebar('Progress','FastSLAM Simulation'); % Start timebar
x(:,1)=x0; % Initialise particle position
pf.xh(:,1)=x0; % Initialise estiamte
y = LaserScanNoise(pf.xh(:,1),map,LRS,sigma_v); % Obtain true laser data from map
% First laser scan data is asserted as occupancy grid TWICE for a very good initialisatio
[P_initial, L_initial] = Occupancy_Grid_Mapping(L, pf.xh(:,1), y, pf.UsableArea, pf.L0, [xg yg], LRS);
[P_initial, L_initial] = Occupancy_Grid_Mapping(L_initial, pf.xh(:,1), y, pf.UsableArea, pf.L0, [xg yg], LRS);
% Initialise all variables at timestep = 1
for i=1:NPC
pf.P(:,:,i)=P_initial;
pf.L(:,:,i)=L_initial;
pf.q(i,1)=1/NPC; % Weights are initialised uniformly
pf.particles(:, i, 1)=x0; % All particles start from the same position
end
%% Start simulation at second timestep
for k = 2:Nstep
timebar(h, k/Nstep)
% True System
% Compute Error Signals
e = sqrt((path(k,1)-x(1,k-1))^2 + (path(k,2)-x(2,k-1))^2) - d;
th = atan2((path(k,2)-x(2,k-1)),(path(k,1)-x(1,k-1)));
% Control Signal
u(1,k-1) = Kp*e;
u(2,k-1) = Kh*(angdiff(th,x(3,k-1)));
% Kinematics
x(:,k) = Kinematics(x(:,k-1),u(:,k-1));
% True LRS data
y = LaserScanNoise(x(:,k),map,LRS,sigma_v);
% The Rao-blackwellized Particle Filter for Grid Based fastSlam
pf.k = k;
[pf.xh(:,k),pf] = RBPF(x(:,k),y,LRS,u(:,k-1),a,pf,Nsamples,'multinomial_resampling');
% Visulaization of true position moving through map
% [pf.P(:,:,1), pf.L(:,:,1)] = Occupancy_Grid_Mapping(pf.L(:,:,1), x(:,k), y, pf.UsableArea, pf.L0, [xg yg]);
% figure(3)
% set(gcf,'units','normalized','outerposition',[1 0 1 1]);
% clf
% imagesc(flipud(pf.P(:,:,1)));
% caxis([0, 1]);
% colormap gray;
% colormap(flipud(colormap));
% hold on;
% grid on;
% plot(x(1,k),x(2,k), 'dr');
% hold off;
end
toc
close(h)
%% Grid end result visualization for all particles: They should be very similar due to resampling stages
figure(88)
for particles=1:pf.NPC
subplot(2,3,particles)
imagesc(pf.P(:,:,particles));
caxis([0, 1]);
colormap gray;
colormap(flipud(colormap));
grid on;
str = sprintf('Grid map for particle %d',particles);
title(str);
hold off;
end
%% State Plots
figure(2)
subplot(3,1,1)
hold on
h1 = plot(squeeze(pf.particles(1,:,:))','y');
h2 = plot(x(1,:));
h3 = plot(pf.xh(1,:),'k');
grid on
title('X Estimation')
xlabel('Samples')
ylabel('Position (dm)')
legend([h1(1) h2 h3],'Particles','X','X_h')
subplot(3,1,2)
hold on
h1 = plot(squeeze(pf.particles(2,:,:))','y');
h2 = plot(x(2,:));
h3 = plot(pf.xh(2,:),'k');
grid on
title('Y Estimation')
xlabel('Samples')
ylabel('Position (dm)')
legend([h1(1) h2 h3],'Particles','X','X_h')
subplot(3,1,3)
hold on
h1 = plot(squeeze(pf.particles(3,:,:))','y');
h2 = plot(x(3,:));
h3 = plot(pf.xh(3,:),'k');
grid on
title('Theta Estimation')
xlabel('Samples')
ylabel('Orientation (rad)')
legend([h1(1) h2 h3],'Particles','X','X_h')
%% Estimation Error
figure(4)
subplot(3,1,1)
plot(x(1,:)-pf.xh(1,:))
grid on
title('X Estimation Error')
xlabel('Samples')
ylabel('Error (dm)')
subplot(3,1,2)
plot(x(2,:)-pf.xh(2,:))
grid on
title('Y Estimation Error')
xlabel('Samples')
ylabel('Error (dm)')
subplot(3,1,3)
plot(x(3,:)-pf.xh(3,:))
grid on
title('Theta Estimation Error')
xlabel('Samples')
ylabel('Error (rad)')