-
Notifications
You must be signed in to change notification settings - Fork 0
/
demo.js
686 lines (614 loc) · 16.5 KB
/
demo.js
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
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
//operating system library. Used to get local IP address
var os = require("os");
//file system library. Used to load file stored inside back end server (https://nodejs.org/api/fs.html)
var fs = require("fs");
//http system library. Handles basic html requests
var http = require("http").createServer(http_handler);
//url library. Used to process html url requests
var url = require("url");
//Websocket
var io = require("socket.io")(http);
//Websocket used to stream video
var websocket = require("ws");
//Communicate with the RPI hardware serial port on the GPIO
var SerialPort = require("serialport");
//-----------------------------------------------------------------------------------
// CONFIGURATION
//-----------------------------------------------------------------------------------
//Port the server will listen to
var server_port = 8080;
var websocket_stream_port = 8082;
//Path of the http and css files for the http server
var file_index_name = "index.html";
var file_css_name = "style.css";
var file_jsplayer_name = "jsmpeg.min.js";
//Http and css files loaded into memory for fast access
var file_index;
var file_css;
var file_jsplayer;
//Name of the local video stream
var stream_name = "mystream";
//-----------------------------------------------------------------------------------
// MOTOR VARIABLES
//-----------------------------------------------------------------------------------
//Speed of the right and left wheels. Arbitrary unit. range from -max_velocity to +max_velocity integer
var vel_r = 0;
var vel_l = 0;
//Minimum and maximum speed allowed
var min_velocity = 0;
var max_velocity = 80;
var velocity = 50;
//Ratio of forward to sideways during turn. 0 full turn, 1 full forward
var steering_ratio = 0.7;
//Map of keys that are down
var key_forward = 0;
var key_backward = 0;
var key_left = 0;
var key_right = 0;
//-----------------------------------------------------------------------------------
// DETECT SERVER OWN IP
//-----------------------------------------------------------------------------------
//If just one interface, store the server IP Here
var server_ip;
//Get local IP address of the server
//https://stackoverflow.com/questions/3653065/get-local-ip-address-in-node-js
var ifaces = os.networkInterfaces();
Object.keys(ifaces).forEach
(
function (ifname)
{
var alias = 0;
ifaces[ifname].forEach
(
function (iface)
{
if ('IPv4' !== iface.family || iface.internal !== false)
{
// skip over internal (i.e. 127.0.0.1) and non-ipv4 addresses
return;
}
if (alias >= 1)
{
// this single interface has multiple ipv4 addresses
console.log('INFO: Server interface ' +alias +' - ' + ifname + ':' + alias, iface.address);
}
else
{
server_ip = iface.address;
// this interface has only one ipv4 adress
console.log('INFO: Server interface - ' +ifname, iface.address);
}
++alias;
}
);
}
);
//-----------------------------------------------------------------------------------
// HTTP SERVER
//-----------------------------------------------------------------------------------
// Fetch and serves local files to client
//Create http server and listen to the given port
http.listen
(
server_port,
function( )
{
console.log('INFO: ' +server_ip +' listening to html requests on port ' +server_port);
//Pre-load http, css and js files into memory to improve http request latency
file_index = load_file( file_index_name );
file_css = load_file( file_css_name );
file_jsplayer = load_file( file_jsplayer_name );
}
);
//-----------------------------------------------------------------------------------
// HTTP REQUESTS HANDLER
//-----------------------------------------------------------------------------------
// Answer to client http requests. Serve http, css and js files
function http_handler(req, res)
{
//If client asks for root
if (req.url == '/')
{
//Request main page
res.writeHead( 200, {"Content-Type": detect_content(file_index_name),"Content-Length":file_index.length} );
res.write(file_index);
res.end();
console.log("INFO: Serving file: " +req.url);
}
//If client asks for css file
else if (req.url == ("/" +file_css_name))
{
//Request main page
res.writeHead( 200, {"Content-Type": detect_content(file_css_name),"Content-Length" :file_css.length} );
res.write(file_css);
res.end();
console.log("INFO: Serving file: " +req.url);
}
//If client asks for css file
else if (req.url == ("/" +file_jsplayer_name))
{
//Request main page
res.writeHead( 200, {"Content-Type": detect_content(file_jsplayer_name),"Content-Length" :file_jsplayer.length} );
res.write(file_jsplayer);
res.end();
console.log("INFO: Serving file: " +req.url);
}
//Listening to the port the stream from ffmpeg will flow into
else if (req.url = "/mystream")
{
res.connection.setTimeout(0);
console.log( "Stream Connected: " +req.socket.remoteAddress + ":" +req.socket.remotePort );
req.on
(
"data",
function(data)
{
streaming_websocket.broadcast(data);
}
);
req.on
(
"end",
function()
{
console.log("local stream has ended");
if (req.socket.recording)
{
req.socket.recording.close();
}
}
);
}
//If client asks for an unhandled path
else
{
res.end();
console.log("ERR: Invalid file request" +req.url);
}
}
//-----------------------------------------------------------------------------------
// WEBSOCKET SERVER: CONTROL/FEEDBACK REQUESTS
//-----------------------------------------------------------------------------------
// Handle websocket connection to the client
io.on
(
"connection",
function (socket)
{
console.log("connecting...");
socket.emit("welcome", { payload: "Server says hello" });
//Periodically send the current server time to the client in string form
setInterval
(
function()
{
socket.emit("server_time", { server_time: get_server_time() });
},
//Send every 333ms
333
);
socket.on
(
"myclick",
function (data)
{
timestamp_ms = get_timestamp_ms();
socket.emit("profile_ping", { timestamp: timestamp_ms });
console.log("button event: " +" client says: " +data.payload);
}
);
//"ArrowLeft"
//When a key is pressed, an event is released once
socket.on
(
"key_down",
function (data)
{
timestamp_ms = get_timestamp_ms();
//socket.emit("profile_ping", { timestamp: timestamp_ms });
//console.log("key up: " +data.payload);
process_key_down( data );
process_robot_velocity();
}
);
//When a key is released, an event is released once
socket.on
(
"key_up",
function (data)
{
timestamp_ms = get_timestamp_ms();
//socket.emit("profile_ping", { timestamp: timestamp_ms });
//console.log("key down: " +data.payload);
process_key_up( data );
process_robot_velocity();
}
);
//profile packets from the client are answer that allows to compute roundway trip time
socket.on
(
"profile_pong",
function (data)
{
timestamp_ms_pong = get_timestamp_ms();
timestamp_ms_ping = data.timestamp;
console.log("Pong received. Round trip time[ms]: " +(timestamp_ms_pong -timestamp_ms_ping));
}
);
}
);
//-----------------------------------------------------------------------------------
// WEBSOCKET SERVER: STREAMING VIDEO
//-----------------------------------------------------------------------------------
// Current toolchain is
// v4l2 -> ffmpeg -(mpeg1 over TS on localhost)-> node -(websocket)-> client -> javascript -> canvas
// Websocket Server
var streaming_websocket = new websocket.Server({port: websocket_stream_port, perMessageDeflate: false});
streaming_websocket.connectionCount = 0;
streaming_websocket.on
(
"connection",
function(socket, upgradeReq)
{
streaming_websocket.connectionCount++;
console.log
(
'New websocket Connection: ',
(upgradeReq || socket.upgradeReq).socket.remoteAddress,
(upgradeReq || socket.upgradeReq).headers['user-agent'],
'('+streaming_websocket.connectionCount+" total)"
);
socket.on
(
'close',
function(code, message)
{
streaming_websocket.connectionCount--;
console.log('Disconnected websocket ('+streaming_websocket.connectionCount+' total)');
}
);
}
);
streaming_websocket.broadcast = function(data)
{
streaming_websocket.clients.forEach
(
function each(client)
{
if (client.readyState === websocket.OPEN)
{
client.send(data);
}
}
);
};
//-----------------------------------------------------------------------------------
// SERIAL PORT
//-----------------------------------------------------------------------------------
// Communication with the HotBlack Hat through GPIO
//Connect to the serial port on th GPIO
var my_uart = new SerialPort
(
"/dev/ttyS0",
{
baudRate: 256000,
openImmediately: true
},
false
);
//-----------------------------------------------------------------------------------
// SERIAL PORT HANDLER
//-----------------------------------------------------------------------------------
// Commands
// "P\0" ping. Communication time out after 1s and motor stop for safety in case of crash
// "F\0" would be signature if RX worked in this demo. Probably an electrical problem on the hat
// "VR%dL%d\0" set speed to motors. -13 to +13 are the caps. over 100 make the hat crash. It's a demo.
//Detect port open
my_uart.on
(
"open",
function()
{
console.log("Port is open!");
//Periodically send the current server time to the client in string form
setInterval
(
function()
{
set_dc_motor_pwm( vel_r, vel_l );
},
//Send periodically speed to the motors
50
);
}
);
//Data from hat. Currently does not work neither in HW nor in SW.
my_uart.on
(
'data',
function(data)
{
console.log('data received: ' + data);
}
);
//-----------------------------------------------------------------------------------
// FUNCTIONS
//-----------------------------------------------------------------------------------
//-----------------------------------------------------------------------------------
// SERVER DATE&TIME
//-----------------------------------------------------------------------------------
// Get server time in string form
function get_server_time()
{
my_date = new Date();
return my_date.toUTCString();
}
//-----------------------------------------------------------------------------------
// TIMESTAMP
//-----------------------------------------------------------------------------------
// Profile performance in ms
function get_timestamp_ms()
{
my_date = new Date();
return 1000.0* my_date.getSeconds() +my_date.getMilliseconds()
}
//-----------------------------------------------------------------------------------
// FILE LOADER
//-----------------------------------------------------------------------------------
// Load files into memory for improved latency
function load_file( file_name )
{
var file_tmp;
var file_path = __dirname +"/" +file_name;
//HTML index file
try
{
file_tmp = fs.readFileSync( file_path );
}
catch (err)
{
console.log("ERR: " +err.code +" failed to load: " +file_path);
throw err;
}
console.log("INFO: " +file_path +" has been loaded into memory");
return file_tmp;
}
//-----------------------------------------------------------------------------------
// CONTENT TYPE DETECTOR
//-----------------------------------------------------------------------------------
// Return the right content type to give correct information to the client browser
function detect_content( file_name )
{
if (file_name.includes(".html"))
{
return "text/html";
}
else if (file_name.includes(".css"))
{
return "text/css";
}
else if (file_name.includes(".js"))
{
return "application/javascript";
}
else
{
throw "invalid extension";
}
}
//-----------------------------------------------------------------------------------
// SEND SERIAL PORT MESSAGES
//-----------------------------------------------------------------------------------
//Send ping message to keep the connection alive
function maze_runner_ping( )
{
my_uart.write
(
"P\0",
function(err, res)
{
if (err)
{
console.log("err ", err);
}
}
);
}
//Compute the PWM set message to send the HotBlack Shield
function set_dc_motor_pwm( vel_r, vel_l )
{
var msg;
//Add plus signs when needed
if ((vel_r > 0) && (vel_l > 0))
{
msg = "PWMR+" + vel_r + "L+" + vel_l + "\0";
}
else if (vel_r > 0)
{
msg = "PWMR+" + vel_r + "L" + vel_l + "\0";
}
else if (vel_l > 0)
{
msg = "PWMR" + vel_r + "L+" + vel_l + "\0";
}
else
{
msg = "PWMR" + vel_r + "L" + vel_l + "\0";
}
my_uart.write
(
msg,
function(err, res)
{
if (err)
{
console.log("err ", err);
}
else
{
console.log("Sent: ", msg);
}
}
);
}
//-----------------------------------------------------------------------------------
// USE KEYBOARD TO MOVE ROBOT
//-----------------------------------------------------------------------------------
//When key is pressed, activate the relevant robot direction
function process_key_down( data )
{
switch(data.payload)
{
//Increase Speed
case "+":
velocity++;
if (velocity > max_velocity)
{
velocity = max_velocity;
}
break;
case "-":
velocity--;
if (velocity < min_velocity)
{
velocity = min_velocity;
}
break;
case "w":
case "W":
key_forward = 1;
break;
case "s":
case "S":
key_backward = 1;
// code block
break;
case "a":
case "A":
key_left = 1;
break;
case "d":
case "D":
key_right = 1;
// code block
break;
default:
//do nothing
break;
}
}
//When key is released, deactivate the relevant robot direction
function process_key_up( data )
{
switch(data.payload)
{
case "w":
case "W":
key_forward = 0;
break;
case "s":
case "S":
key_backward = 0;
// code block
break;
case "a":
case "A":
key_left = 0;
break;
case "d":
case "D":
key_right = 0;
// code block
break;
default:
//do nothing
break;
}
}
//-----------------------------------------------------------------------------------
// COMPUTE MOTOR SPEED FROM DIRECTION
//-----------------------------------------------------------------------------------
// Based on the keys down and the top speed process the speed to send to the motors
function process_robot_velocity()
{
//Detect number of keys down
var sum = key_forward +key_backward +key_left +key_right;
//console.log("INFO: ", key_forward, key_backward, key_left, key_right);
//No keys. Robot stopped
if (sum == 0)
{
//robot is stopped
vel_r = 0;
vel_l = 0;
}
//Full in one direction
else if (sum == 1)
{
if (key_forward == 1)
{
//Both motors are forward at maximum velocity
vel_r = velocity;
vel_l = velocity;
}
else if (key_backward == 1)
{
//Both motors are forward at maximum velocity
vel_r = -velocity;
vel_l = -velocity;
}
else if (key_right == 1)
{
//Both motors are forward at maximum velocity
vel_r = -velocity;
vel_l = velocity;
}
else if (key_left == 1)
{
//Both motors are forward at maximum velocity
vel_r = velocity;
vel_l = -velocity;
}
else
{
}
}
//Two keys down. Not all eight combination are valid
else if (sum == 2)
{
if ((key_forward == 1) && (key_right == 1))
{
//Weaken one motor to turn
vel_r = Math.floor(velocity*steering_ratio);
vel_l = velocity;
}
else if ((key_forward == 1) && (key_left == 1))
{
//Weaken one motor to turn
vel_r = velocity;
vel_l = Math.floor(velocity*steering_ratio);
}
else if ((key_backward == 1) && (key_right == 1))
{
//Weaken one motor to turn
vel_r = Math.floor(velocity*steering_ratio);
vel_l = velocity;
}
else if ((key_backward == 1) && (key_left == 1))
{
//Weaken one motor to turn
vel_r = velocity;
vel_l = Math.floor(velocity*steering_ratio);
}
else
{
//do nothing, the user did a mistake
//Hold previous speed
}
}
//three keys and above maintain previous direction
else
{
//the user just pressed one more while switching key
//do nothing
}
}