-
Notifications
You must be signed in to change notification settings - Fork 5
Expand file tree
/
Copy pathArduino_control
More file actions
669 lines (585 loc) · 17.7 KB
/
Arduino_control
File metadata and controls
669 lines (585 loc) · 17.7 KB
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
#include "esp_camera.h"
#include <Arduino.h>
#include <WiFi.h>
#include <AsyncTCP.h>
#include <ESPAsyncWebServer.h>
#include <iostream>
#include <sstream>
struct MOTOR_PINS
{
int pinEn;
int pinIN1;
int pinIN2;
};
std::vector<MOTOR_PINS> motorPins =
{
{2, 12, 13}, //RIGHT_MOTOR Pins (EnA, IN1, IN2)
{2, 1, 3}, //LEFT_MOTOR Pins (EnB, IN3, IN4)
};
#define LIGHT_PIN 4
#define UP 1
#define DOWN 2
#define LEFT 3
#define RIGHT 4
#define STOP 0
#define RIGHT_MOTOR 0
#define LEFT_MOTOR 1
#define FORWARD 1
#define BACKWARD -1
const int PWMFreq = 1000; /* 1 KHz */
const int PWMResolution = 8;
const int PWMSpeedChannel = 2;
const int PWMLightChannel = 3;
//Camera related constants
#define PWDN_GPIO_NUM 32
#define RESET_GPIO_NUM -1
#define XCLK_GPIO_NUM 0
#define SIOD_GPIO_NUM 26
#define SIOC_GPIO_NUM 27
#define Y9_GPIO_NUM 35
#define Y8_GPIO_NUM 34
#define Y7_GPIO_NUM 39
#define Y6_GPIO_NUM 36
#define Y5_GPIO_NUM 21
#define Y4_GPIO_NUM 19
#define Y3_GPIO_NUM 18
#define Y2_GPIO_NUM 5
#define VSYNC_GPIO_NUM 25
#define HREF_GPIO_NUM 23
#define PCLK_GPIO_NUM 22
const char* ssid = "Srover";
const char* password = "12345678";
AsyncWebServer server(80);
AsyncWebSocket wsCamera("/Camera");
AsyncWebSocket wsCarInput("/CarInput");
uint32_t cameraClientId = 0;
const char* htmlHomePage PROGMEM = R"HTMLHOMEPAGE(
<!DOCTYPE html>
<html>
<head>
<meta name="viewport" content="width=device-width, initial-scale=1, maximum-scale=1, user-scalable=no">
<script>
window.addEventListener('keyup', arrowUp)
window.addEventListener('keydown', arrowDown)
function arrowDown(e) {
const key = document.querySelector(.arrow-key[data-key="${e.keyCode}"]);
key.classList.add('press')
}
function arrowUp(e) {
const key = document.querySelector(.arrow-key[data-key="${e.keyCode}"]);
key.classList.remove('press')
}
</script>
<style>
.slider-container {
display: flex;
flex-direction: column;
align-items: flex-start;
margin-left: 20px;
}
.slider {
-webkit-appearance: none;
width: 200px;
height: 15px;
border-radius: 5px;
background: #d3d3d3;
outline: none;
opacity: 0.7;
-webkit-transition: .2s;
transition: opacity .2s;
margin-bottom: 10px;
}
.slider:hover {
opacity: 1;
}
.slider::-webkit-slider-thumb {
-webkit-appearance: none;
appearance: none;
width: 25px;
height: 25px;
border-radius: 50%;
background: rgb(36, 36, 36);
cursor: pointer;
}
.slider::-moz-range-thumb {
width: 25px;
height: 25px;
border-radius: 50%;
background: red;
cursor: pointer;
}
* {
box-sizing: border-box;
&:before,
&:after {
box-sizing: border-box;
}
user-select: none;
z-index: 10;
}
html {
height: 100%;
margin: 0;
overflow: auto;
padding: 0;
width: 100%;
}
body {
align-content: center;
background: #ECE9E6;
background: -webkit-linear-gradient(to left, #ECE9E6, #FFFFFF);
background: linear-gradient(to left, #ECE9E6, #FFFFFF);
display: flex;
flex-direction: column;
height: 100%;
justify-content: center;
margin: 0;
overflow: auto;
padding: 0;
width: 100%;
}
h1 {
font-family: Helvetica, Arial;
text-align: center;
}
.arrow-key-container {
display: inline-block;
text-align: center;
transform: translate3d(0, 0, 0);
}
.arrow-key {
align-items: center;
background: #ccc;
border-radius: 6px;
box-shadow: -1px 1px 0 #999, -2px 2px 0 #999, -3px 3px 0 #999, -4px 4px 0 #999;
color: #fff;
display: inline-flex;
font-size: 30px;
font-weight: bold;
height: 50px;
width: 50px;
justify-content: center;
margin: 5px;
transform: translate3d(0, 0, 0);
transition: box-shadow .1s linear, transform .1s linear;
&:active,
&.press {
box-shadow: 0px 0px 0 #999, 0px 0px 0 #999, 0px 0px 0 #999, -1px 1px 0 #999;
transform: translate3d(-3px, 3px, 0);
}
&.left:before {
content: "\2190";
}
&.up:before {
content: "\2191";
}
&.down:before {
content: "\2193";
}
&.right:before {
content: "\2192";
}
}
.button-container {
position: absolute;
top: 70%;
right: 5%;
}
.slider-container {
position: absolute;
top: 70%;
left: 5%;
}
.slider-container2 {
position: absolute;
top: 35%;
right: 5%;
transform: rotate(270deg);
}
</style>
</head>
<body class="noselect" align="center" style="background-color:white">
<div class="slider-container2">
<p>
Speed
</p>
<input type="range" min="0" max="255" value="150" class="slider speed" id="Speed"
oninput='sendButtonInput("Speed",value)'>
<br>
<p>
Flash
</p>
<input type="range" min="0" max="255" value="0" class="slider light" id="Light"
oninput='sendButtonInput("Light",value)'>
</div>
<div class="button-container">
<div class="arrow-key up" data-key="38" onkeydown='sendButtonInput("MoveCar","1")'
onkeyup='sendButtonInput("MoveCar","0")' ontouchstart='sendButtonInput("MoveCar","1")'
ontouchend='sendButtonInput("MoveCar","0")'>
</div>
<br>
<div class="arrow-key left" data-key="37" onkeydown='sendButtonInput("MoveCar","3")'
onkeyup='sendButtonInput("MoveCar","0")' ontouchstart='sendButtonInput("MoveCar","3")'
ontouchend='sendButtonInput("MoveCar","0")'>
</div>
<div class="arrow-key down" data-key="40" onkeydown='sendButtonInput("MoveCar","2")'
onkeyup='sendButtonInput("MoveCar","0")' ontouchstart='sendButtonInput("MoveCar","2")'
ontouchend='sendButtonInput("MoveCar","0")'>
</div>
<div class=" arrow-key right" data-key="39" onkeydown='sendButtonInput("MoveCar","4")'
onkeyup='sendButtonInput("MoveCar","0")' ontouchstart='sendButtonInput("MoveCar","4")'
ontouchend='sendButtonInput("MoveCar","0")'>
</div>
</div>
<img id="cameraImage" src="" style="width: 640px ; height: 360px; align-self: center; position:absolute; top:5% ">
<script>
window.addEventListener('keyup', arrowUp)
window.addEventListener('keydown', arrowDown)
function arrowDown(e) {
const key = document.querySelector(.arrow-key[data-key="${e.keyCode}"]);
key.classList.add('press')
}
function arrowUp(e) {
const key = document.querySelector(.arrow-key[data-key="${e.keyCode}"]);
key.classList.remove('press')
}
var webSocketCameraUrl = "ws:\/\/" + window.location.hostname + "/Camera";
var webSocketCarInputUrl = "ws:\/\/" + window.location.hostname + "/CarInput";
var websocketCamera;
var websocketCarInput;
function initCameraWebSocket()
{
websocketCamera = new WebSocket(webSocketCameraUrl);
websocketCamera.binaryType = 'blob';
websocketCamera.onopen = function(event){};
websocketCamera.onclose = function(event){setTimeout(initCameraWebSocket, 2000);};
websocketCamera.onmessage = function(event)
{
var imageId = document.getElementById("cameraImage");
imageId.src = URL.createObjectURL(event.data);
};
}
function initCarInputWebSocket()
{
websocketCarInput = new WebSocket(webSocketCarInputUrl);
websocketCarInput.onopen = function(event)
{
sendButtonInput("Speed", document.getElementById("Speed").value);
sendButtonInput("Light", document.getElementById("Light").value);
};
websocketCarInput.onclose = function(event){setTimeout(initCarInputWebSocket, 2000);};
websocketCarInput.onmessage = function(event){};
}
function initWebSocket()
{
initCameraWebSocket ();
initCarInputWebSocket();
}
function sendButtonInput(key, value)
{
var data = key + "," + value;
websocketCarInput.send(data);
}
window.onload = initWebSocket;
document.getElementById("mainTable").addEventListener("touchend", function(event){
event.preventDefault()
});
</script>
</body>
</html>
)HTMLHOMEPAGE";
void rotateMotor(int motorNumber, int motorDirection)
{
if (motorDirection == FORWARD)
{
digitalWrite(motorPins[motorNumber].pinIN1, HIGH);
digitalWrite(motorPins[motorNumber].pinIN2, LOW);
}
else if (motorDirection == BACKWARD)
{
digitalWrite(motorPins[motorNumber].pinIN1, LOW);
digitalWrite(motorPins[motorNumber].pinIN2, HIGH);
}
else
{
digitalWrite(motorPins[motorNumber].pinIN1, LOW);
digitalWrite(motorPins[motorNumber].pinIN2, LOW);
}
}
void moveCar(int inputValue)
{
Serial.printf("Got value as %d\n", inputValue);
switch(inputValue)
{
case UP:
rotateMotor(RIGHT_MOTOR, FORWARD);
rotateMotor(LEFT_MOTOR, FORWARD);
break;
case DOWN:
rotateMotor(RIGHT_MOTOR, BACKWARD);
rotateMotor(LEFT_MOTOR, BACKWARD);
break;
case LEFT:
rotateMotor(RIGHT_MOTOR, FORWARD);
rotateMotor(LEFT_MOTOR, BACKWARD);
break;
case RIGHT:
rotateMotor(RIGHT_MOTOR, BACKWARD);
rotateMotor(LEFT_MOTOR, FORWARD);
break;
case STOP:
rotateMotor(RIGHT_MOTOR, STOP);
rotateMotor(LEFT_MOTOR, STOP);
break;
default:
rotateMotor(RIGHT_MOTOR, STOP);
rotateMotor(LEFT_MOTOR, STOP);
break;
}
}
const char* htmlCameraPage PROGMEM = R"=====(
<!DOCTYPE html>
<html>
<head>
<title>Camera Feed</title>
<style>
body, html {
margin: 0;
padding: 0;
width: 100%;
height: 100%;
overflow: hidden;
}
#cameraImage {
width: 100%;
height: 100%;
object-fit: cover;
position: absolute;
top: 0;
left: 0;
}
</style>
</head>
<body>
<img id="cameraImage" src="">
<script>
var webSocketCameraUrl = "ws:\/\/" + window.location.hostname + "/Camera";
var websocketCamera;
function initCameraWebSocket()
{
websocketCamera = new WebSocket(webSocketCameraUrl);
websocketCamera.binaryType = 'blob';
websocketCamera.onopen = function(event){};
websocketCamera.onclose = function(event){setTimeout(initCameraWebSocket, 2000);};
websocketCamera.onmessage = function(event)
{
var imageId = document.getElementById("cameraImage");
imageId.src = URL.createObjectURL(event.data);
};
}
window.onload = initCameraWebSocket;
</script>
</body>
</html>
)=====";
void handleCamera(AsyncWebServerRequest *request)
{
request->send_P(200, "text/html", htmlCameraPage);
}
void handleRoot(AsyncWebServerRequest *request)
{
request->send_P(200, "text/html", htmlHomePage);
}
void handleNotFound(AsyncWebServerRequest *request)
{
request->send(404, "text/plain", "File Not Found");
}
void onCarInputWebSocketEvent(AsyncWebSocket *server,
AsyncWebSocketClient *client,
AwsEventType type,
void *arg,
uint8_t *data,
size_t len)
{
switch (type)
{
case WS_EVT_CONNECT:
Serial.printf("WebSocket client #%u connected from %s\n", client->id(), client->remoteIP().toString().c_str());
break;
case WS_EVT_DISCONNECT:
Serial.printf("WebSocket client #%u disconnected\n", client->id());
moveCar(0);
ledcWrite(PWMLightChannel, 0);
break;
case WS_EVT_DATA:
AwsFrameInfo *info;
info = (AwsFrameInfo*)arg;
if (info->final && info->index == 0 && info->len == len && info->opcode == WS_TEXT)
{
std::string myData = "";
myData.assign((char *)data, len);
std::istringstream ss(myData);
std::string key, value;
std::getline(ss, key, ',');
std::getline(ss, value, ',');
Serial.printf("Key [%s] Value[%s]\n", key.c_str(), value.c_str());
int valueInt = atoi(value.c_str());
if (key == "MoveCar")
{
moveCar(valueInt);
}
else if (key == "Speed")
{
ledcWrite(PWMSpeedChannel, valueInt);
}
else if (key == "Light")
{
ledcWrite(PWMLightChannel, valueInt);
}
}
break;
case WS_EVT_PONG:
case WS_EVT_ERROR:
break;
default:
break;
}
}
void onCameraWebSocketEvent(AsyncWebSocket *server,
AsyncWebSocketClient *client,
AwsEventType type,
void *arg,
uint8_t *data,
size_t len)
{
switch (type)
{
case WS_EVT_CONNECT:
Serial.printf("WebSocket client #%u connected from %s\n", client->id(), client->remoteIP().toString().c_str());
cameraClientId = client->id();
break;
case WS_EVT_DISCONNECT:
Serial.printf("WebSocket client #%u disconnected\n", client->id());
cameraClientId = 0;
break;
case WS_EVT_DATA:
break;
case WS_EVT_PONG:
case WS_EVT_ERROR:
break;
default:
break;
}
}
void setupCamera()
{
camera_config_t config;
config.ledc_channel = LEDC_CHANNEL_4;
config.ledc_timer = LEDC_TIMER_2;
config.pin_d0 = Y2_GPIO_NUM;
config.pin_d1 = Y3_GPIO_NUM;
config.pin_d2 = Y4_GPIO_NUM;
config.pin_d3 = Y5_GPIO_NUM;
config.pin_d4 = Y6_GPIO_NUM;
config.pin_d5 = Y7_GPIO_NUM;
config.pin_d6 = Y8_GPIO_NUM;
config.pin_d7 = Y9_GPIO_NUM;
config.pin_xclk = XCLK_GPIO_NUM;
config.pin_pclk = PCLK_GPIO_NUM;
config.pin_vsync = VSYNC_GPIO_NUM;
config.pin_href = HREF_GPIO_NUM;
config.pin_sscb_sda = SIOD_GPIO_NUM;
config.pin_sscb_scl = SIOC_GPIO_NUM;
config.pin_pwdn = PWDN_GPIO_NUM;
config.pin_reset = RESET_GPIO_NUM;
config.xclk_freq_hz = 20000000;
config.pixel_format = PIXFORMAT_JPEG;
config.frame_size = FRAMESIZE_VGA;
config.jpeg_quality = 10;
config.fb_count = 1;
// camera init
esp_err_t err = esp_camera_init(&config);
if (err != ESP_OK)
{
Serial.printf("Camera init failed with error 0x%x", err);
return;
}
if (psramFound())
{
heap_caps_malloc_extmem_enable(20000);
Serial.printf("PSRAM initialized. malloc to take memory from psram above this size");
}
}
void sendCameraPicture()
{
if (cameraClientId == 0)
{
return;
}
unsigned long startTime1 = millis();
//capture a frame
camera_fb_t * fb = esp_camera_fb_get();
if (!fb)
{
Serial.println("Frame buffer could not be acquired");
return;
}
unsigned long startTime2 = millis();
wsCamera.binary(cameraClientId, fb->buf, fb->len);
esp_camera_fb_return(fb);
//Wait for message to be delivered
while (true)
{
AsyncWebSocketClient * clientPointer = wsCamera.client(cameraClientId);
if (!clientPointer || !(clientPointer->queueIsFull()))
{
break;
}
delay(1);
}
unsigned long startTime3 = millis();
Serial.printf("Time taken Total: %d|%d|%d\n",startTime3 - startTime1, startTime2 - startTime1, startTime3-startTime2 );
}
void setUpPinModes()
{
//Set up PWM
ledcSetup(PWMSpeedChannel, PWMFreq, PWMResolution);
ledcSetup(PWMLightChannel, PWMFreq, PWMResolution);
for (int i = 0; i < motorPins.size(); i++)
{
pinMode(motorPins[i].pinEn, OUTPUT);
pinMode(motorPins[i].pinIN1, OUTPUT);
pinMode(motorPins[i].pinIN2, OUTPUT);
/* Attach the PWM Channel to the motor enb Pin */
ledcAttachPin(motorPins[i].pinEn, PWMSpeedChannel);
}
moveCar(STOP);
pinMode(LIGHT_PIN, OUTPUT);
ledcAttachPin(LIGHT_PIN, PWMLightChannel);
}
void setup(void)
{
setUpPinModes();
//Serial.begin(115200);
WiFi.softAP(ssid, password);
IPAddress IP = WiFi.softAPIP();
Serial.print("AP IP address: ");
Serial.println(IP);
server.on("/", HTTP_GET, handleRoot);
server.onNotFound(handleNotFound);
server.on("/camera", HTTP_GET, handleCamera);
wsCamera.onEvent(onCameraWebSocketEvent);
server.addHandler(&wsCamera);
wsCarInput.onEvent(onCarInputWebSocketEvent);
server.addHandler(&wsCarInput);
server.begin();
Serial.println("HTTP server started");
setupCamera();
}
void loop()
{
wsCamera.cleanupClients();
wsCarInput.cleanupClients();
sendCameraPicture();
Serial.printf("SPIRam Total heap %d, SPIRam Free Heap %d\n", ESP.getPsramSize(), ESP.getFreePsram());
}