-
Notifications
You must be signed in to change notification settings - Fork 4
/
Copy pathsgd_slam.html
406 lines (310 loc) · 13.2 KB
/
sgd_slam.html
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
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
<!--
Stochastic Gradient Descent SLAM
Implementation of SLAM by SGD graph optimization by Olson et al. (2006)
Paper link:
http://rvsn.csail.mit.edu/content/eolson/graphoptim/eolson-graphoptim2006.pdf
@author odestcj / https://github.com/odestcj
Forgive my coding style. I am still a typedef struct kind of guy
with a noticeable disregard for proper scoping
Note: the original implementation used threejs, but maved to HTML5 Canvas
It should relatively simple to convert rendering to threejs
-->
<html>
<body>
<!-- //////////////////////////////////////////////////
///// JAVASCRIPT INCLUDES
////////////////////////////////////////////////// -->
<!-- threejs - https://github.com/mrdoob/three.js/ -->
<script src="js/three.min.js"></script>
<!-- threejs camera controls helpers -->
<script src="js/OrbitControls.js"></script>
<!-- threejs keyboard input helper -->
<script src="js/THREEx.KeyboardState.js"></script>
<!-- odestcj's matrix routines -->
<script src="js/3jsbot_matrix.js"></script>
<!-- numericjs used for matrix inversion -->
<script src="js/numeric-1.2.6.min.js"></script>
<script>
//////////////////////////////////////////////////
///// MAIN FUNCTION CALLS
//////////////////////////////////////////////////
// initialize threejs scene, user input, and robot kinematics
init();
// main animation loop maintained by threejs
animate();
//////////////////////////////////////////////////
///// INITIALIZATION FUNCTION DEFINITONS
//////////////////////////////////////////////////
function init() {
landmarks = []; // locations of landmarks
poses = []; // true poses of the robot from noiseless odometry
estimates = []; // estimated poses of true robot pose from noisy observations
odometry_pose = []; // poses observed from directly from odometry observations
constraints = []; // constraints between poses
iters = 0; // number of optimization iterations that have occurred
// create landmarks (ignored for now)
for (i=0;i<3;i++) {
landmarks[i] = { location:[i*10*3,3*10*(i%2-0.5)] }; // (x,z)
}
var i,j,i_start;
// truth pose of the robot
var truth_pose = [0,0,0];
// pose of the robot with noisy odometry
var noise_pose = [0,0,0];
// generate trajectory of the robot
//for (i=0;i<81;i++) {
//for (i=0;i<1280;i++) {
for (i=0;i<320;i++) {
//for (i=0;i<640;i++) {
// movement commands (continual loop)
if (i<10) odometry = [10,0,0];
else if (i%10<1) odometry = [0,0,Math.PI/2];
else odometry = [10,0,0];
// integrate true movement of robot into truth pose
truth_pose[2] += odometry[2];
truth_pose[0] += odometry[0]*Math.cos(truth_pose[2]) + -odometry[1]*Math.sin(truth_pose[2]);
truth_pose[1] += odometry[0]*Math.sin(truth_pose[2]) + odometry[1]*Math.cos(truth_pose[2]);
poses[i] = { pose:[truth_pose[0],truth_pose[1],truth_pose[2]] }; // (x,z,angle)
// add noise to current odometry observations
noise_odometry = [
odometry[0]+0.05*(Math.random()-0.5),
odometry[1]+0.05*(Math.random()-0.5),
odometry[2]+0.2*(Math.random()-0.5)
];
// integrate movement observations of robot into odometric pose
noise_pose[2] += noise_odometry[2];
noise_pose[0] += noise_odometry[0]*Math.cos(noise_pose[2]) + -noise_odometry[1]*Math.sin(noise_pose[2]);
noise_pose[1] += noise_odometry[0]*Math.sin(noise_pose[2]) + noise_odometry[1]*Math.cos(noise_pose[2]);
estimates[i] = { pose:[noise_pose[0],noise_pose[1],noise_pose[2]] }; // (x,z,angle)
odometry_pose[i] = { pose:[noise_pose[0],noise_pose[1],noise_pose[2]] }; // (x,z,angle)
// (DO NOT USE THIS, will overconstrain system)
// add constraint between poses adjacent in time based on observed odometry and expected noise
/*
if (i > 0) {
constraints[i-1] = {a:i-1,b:i,t:noise_odometry,sigma:[[0.05,0,0],[0,0.05,0],[0,0,0.2]]};
}
*/
}
// constraints for loop closures
constraints[constraints.length] = {a:0,b:40,t:[0,0,0],sigma:[[0.2,0,0],[0,0.2,0],[0,0,0.2]]};
for (i=1;i<estimates.length-40;i++) {
constraints[constraints.length] = {a:i,b:i+40,t:[0,0,0],sigma:[[0.2,0,0],[0,0.2,0],[0,0,0.2]]};
}
/* more constaints
*/
for (i=1;i<estimates.length-40;i+=7) {
for (j=i+80;j<estimates.length-40;j+=40) {
constraints[constraints.length] = {a:i,b:j,t:[0,0,0],sigma:[[0.2,0,0],[0,0.2,0],[0,0,0.2]]};
}
}
// made M a global variable to save on memory
M = new Array(poses.length);
for (i=0;i<poses.length;i++) {
M[i] = [0,0,0];
}
mark_time = Date.now();
}
//////////////////////////////////////////////////
///// ANIMATION AND INTERACTION LOOP
//////////////////////////////////////////////////
function animate() {
// note: three.js includes requestAnimationFrame shim
// alternative to using setInterval for updating in-browser drawing
// this effectively request that the animate function be called again for next draw
// http://learningwebgl.com/blog/?p=3189
requestAnimationFrame( animate );
if (Date.now()-mark_time > 100)
mark_time = Date.now();
else
return;
// SGD update
var i;
iters++;
gamma = [100000000000,100000000000,100000000000];
//var M = new Array(poses.length);
//for (i=0;i<poses.length;i++) {
// M[i] = [0,0,0];
//}
// made M a global variable to save on memory
for (i=0;i<poses.length;i++) {
M[i][0] = 0;
M[i][1] = 0;
M[i][2] = 0;
}
for (i=0;i<constraints.length;i++) {
var R = [
[Math.cos(estimates[constraints[i].a].pose[2]),-Math.sin(estimates[constraints[i].a].pose[2]),0],
[Math.sin(estimates[constraints[i].a].pose[2]),Math.cos(estimates[constraints[i].a].pose[2]),0],
[0,0,1] ];
var W = numeric.inv(matrix_multiply(matrix_multiply(R,constraints[i].sigma),matrix_transpose(R)));
for (k=constraints[i].a+1;k<=constraints[i].b;k++) {
M[k][0] += W[0][0];
M[k][1] += W[1][1];
M[k][2] += W[2][2];
// not sure this is right
/*
gamma[0] = Math.min(gamma[0],W[0][0]);
gamma[1] = Math.min(gamma[1],W[1][1]);
gamma[2] = Math.min(gamma[2],W[2][2]);
*/
if (((gamma[0]*gamma[0])+(gamma[1]*gamma[1])+(gamma[2]*gamma[2]))>(W[0][0]*W[0][0]+(W[1][1]*W[1][1])+(W[2][2]*W[2][2]))) {
gamma[0] = W[0][0];
gamma[1] = W[1][1];
gamma[2] = W[2][2];
}
}
}
for (i=0;i<constraints.length;i++) {
var Pa = [
[Math.cos(estimates[constraints[i].a].pose[2]),-Math.sin(estimates[constraints[i].a].pose[2]),estimates[constraints[i].a].pose[0]],
[Math.sin(estimates[constraints[i].a].pose[2]),Math.cos(estimates[constraints[i].a].pose[2]),estimates[constraints[i].a].pose[1]],
[0,0,1] ];
var R = [
[Pa[0][0],Pa[0][1],0],
[Pa[1][0],Pa[1][1],0],
[0,0,1] ];
var Tab = [
[Math.cos(constraints[i].t[2]),-Math.sin(constraints[i].t[2]),constraints[i].t[0]],
[Math.sin(constraints[i].t[2]),Math.cos(constraints[i].t[2]),constraints[i].t[1]],
[0,0,1]];
var Pb_prime = matrix_multiply(Pa,Tab);
//var r = [ //??? is Pb_prime a vector or a matrix?
// [Pb_prime[0]-estimates[constraints[i].b].pose[0]],
// [Pb_prime[1]-estimates[constraints[i].b].pose[1]],
// [Pb_prime[2]-estimates[constraints[i].b].pose[2]]
//];
// grab pose b's angle through vector transformed by Pb_prime rotation
tempvec = [[1],[0],[0]];
temprotvec = matrix_multiply(Pb_prime,tempvec);
pb_prime_rot = Math.atan2(temprotvec[1],temprotvec[0]);
tempvec = [[0],[0],[1]];
pb_prime_trn = matrix_multiply(Pb_prime,tempvec);
var r = [
//[Pb_prime[0][2]-estimates[constraints[i].b].pose[0]],
[pb_prime_trn[0][0]-estimates[constraints[i].b].pose[0]],
//[Pb_prime[1][2]-estimates[constraints[i].b].pose[1]],
[pb_prime_trn[1][0]-estimates[constraints[i].b].pose[1]],
[pb_prime_rot-estimates[constraints[i].b].pose[2]]
];
// mod2pi(r_3)
while (r[2][0] > 2*Math.PI) r[2][0] -= 2*Math.PI;
while (r[2][0] < 0) r[2][0] += 2*Math.PI;
var d_temp = matrix_multiply(numeric.inv(matrix_multiply(matrix_multiply(matrix_transpose(R),constraints[i].sigma),R)),r);
d_temp[0][0] *= 2;
d_temp[1][0] *= 2;
d_temp[2][0] *= 2;
for (j=0;j<3;j++) {
//var alpha = 1/(gamma[j]*Math.pow(iters,0.5));
var alpha = 1/(gamma[j]*Math.pow(iters,0.8));
var alpha = 1/(gamma[j]*iters);
totalweight = 0;
for (k=(constraints[i].a)+1;k<=constraints[i].b;k++) {
totalweight += 1/M[k][j];
}
var beta = (constraints[i].b-constraints[i].a)*d_temp[j]*alpha;
if (Math.abs(beta) > Math.abs(r[j][0])) {
beta = r[j][0];
beta_residual = true;
}
else {
beta_residual = false;
}
delta_pose = 0;
for (k=constraints[i].a+1;k<estimates.length;k++) {
if ((k >= (constraints[i].a)+1)&&(k <= constraints[i].b)) {
delta_pose += beta/M[k][j]/totalweight;
}
estimates[k].pose[j] += delta_pose;
}
}
}
// DRAWING
// get canvas element in document and drawing context
c = document.getElementById("myCanvas");
ctx = c.getContext("2d");
// clear canvas
ctx.clearRect(0,0,c.width,c.height);
// draw text labels
ctx.fillStyle = "#000000";
ctx.font = "14px Arial";
ctx.fillText("True trajectory",-100+c.width/2,-150+c.height/2);
ctx.fillText("Observed trajectory",100+c.width/2,-150+c.height/2);
ctx.fillText("Estimated trajectory",c.width/2,50+c.height/2);
// draw true robot poses
ctx.fillStyle = "#8888AA";
for (i=0;i<poses.length;i++) {
ctx.fillRect((poses[i].pose[0]-2)-100+c.width/2,(poses[i].pose[1]-2)-100+c.height/2,4,4);
}
// draw trajectory for true robot poses
ctx.fillStyle = "#0000FF";
for (i=0;i<poses.length-1;i++) {
ctx.beginPath();
ctx.moveTo((poses[i].pose[0])-100+c.width/2,(poses[i].pose[1])-100+c.height/2,4,4);
ctx.lineTo((poses[i+1].pose[0])-100+c.width/2,(poses[i+1].pose[1])-100+c.height/2,4,4);
ctx.stroke();
}
// draw landmark positions (not current used)
/*
ctx.fillStyle = "#FF0000";
for (i=0;i<landmarks.length;i++) {
ctx.fillRect((landmarks[i].location[0]-2)+c.width/2,(landmarks[i].location[1]-2)+c.height/2,4,4);
}
*/
// draw robot pose estimates
ctx.fillStyle = "#88AA88";
if (beta_residual) // use a different color when step rate is high
ctx.fillStyle = "#FFAAFF";
for (i=0;i<estimates.length;i++) {
ctx.fillRect((estimates[i].pose[0]-2)+c.width/2,(estimates[i].pose[1]-2)+100+c.height/2,4,4);
}
// draw trajectory between robot pose estimates
ctx.fillStyle = "#00FF00";
for (i=0;i<estimates.length-1;i++) {
ctx.beginPath();
ctx.moveTo((estimates[i].pose[0])+c.width/2,(estimates[i].pose[1])+100+c.height/2,4,4);
ctx.lineTo((estimates[i+1].pose[0])+c.width/2,(estimates[i+1].pose[1])+100+c.height/2,4,4);
ctx.stroke();
}
// draw odometry poses
ctx.fillStyle = "#88AA88";
for (i=0;i<odometry_pose.length;i++) {
ctx.fillRect((odometry_pose[i].pose[0]-2)+100+c.width/2,(odometry_pose[i].pose[1]-2)-100+c.height/2,4,4);
}
// draw trajectory between odometry poses
ctx.fillStyle = "#00FF00";
for (i=0;i<odometry_pose.length-1;i++) {
ctx.beginPath();
ctx.moveTo((odometry_pose[i].pose[0])+100+c.width/2,(odometry_pose[i].pose[1])-100+c.height/2,4,4);
ctx.lineTo((odometry_pose[i+1].pose[0])+100+c.width/2,(odometry_pose[i+1].pose[1])-100+c.height/2,4,4);
ctx.stroke();
}
/* threejs keyboard and rendering calls
if ( keyboard.pressed("d") )
pendulum.control += 0.05;
else if ( keyboard.pressed("a") )
pendulum.control += -0.05;
if ( keyboard.pressed("e") )
pendulum.desired += 0.05;
if ( keyboard.pressed("q") )
pendulum.desired += -0.05;
textbar.innerHTML =
" t = " + t.toFixed(2) +
" dt = " + dt.toFixed(2) +
" x = " + pendulum.angle.toFixed(2) +
" x_dot = " + pendulum.angle_dot.toFixed(2) +
" x_desired = " + pendulum.desired.toFixed(2) +
" u = " + pendulum.control.toFixed(2) +
" m = " + pendulum.mass.toFixed(2) +
" l = " + pendulum.length.toFixed(2) +
" integrator = " + numerical_integrator
;
// threejs rendering update
renderer.render( scene, camera );
*/
}
</script>
<canvas id="myCanvas" width=600 height=600
style="z-index: 10 ;border:1px solid #000000;">
</canvas>
</body>
</html>