-
Notifications
You must be signed in to change notification settings - Fork 0
/
server.cpp
338 lines (303 loc) · 10.6 KB
/
server.cpp
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
#include "arduino.h"
#include "esp_camera.h"
#include "esp_timer.h"
#include "img_converters.h"
#include "globals.h"
#include "server.h"
#include "index_html_content.h"
#if defined(ARDUINO_ARCH_ESP32) && defined(CONFIG_ARDUHAL_ESP_LOG)
#include "esp32-hal-log.h"
#define TAG ""
#else
#include "esp_log.h"
static const char *TAG = "SERVER";
#endif
#define PART_BOUNDARY "123456789000000000000987654321"
static const char *_STREAM_CONTENT_TYPE = "multipart/x-mixed-replace;boundary=" PART_BOUNDARY;
static const char *_STREAM_BOUNDARY = "\r\n--" PART_BOUNDARY "\r\n";
static const char *_STREAM_PART = "Content-Type: image/jpeg\r\nContent-Length: %u\r\n\r\n";
httpd_handle_t server_httpd = NULL;
httpd_handle_t stream_httpd = NULL;
static esp_err_t index_handler(httpd_req_t *req) {
httpd_resp_set_type(req, "text/html");
return httpd_resp_send(req, (const char *)INDEX_HTML, strlen(INDEX_HTML));
}
esp_err_t parse_get(httpd_req_t *req, char **obuf) {
char *buf = NULL;
size_t buf_len = 0;
buf_len = httpd_req_get_url_query_len(req) + 1;
if (buf_len > 1) {
buf = (char *)malloc(buf_len);
if (!buf) {
httpd_resp_send_500(req);
return ESP_FAIL;
}
if (httpd_req_get_url_query_str(req, buf, buf_len) == ESP_OK) {
*obuf = buf;
return ESP_OK;
}
free(buf);
}
httpd_resp_send_404(req);
return ESP_FAIL;
}
static int print_reg(char *p, sensor_t *s, uint16_t reg, uint32_t mask) {
return sprintf(p, "\"0x%x\":%u,", reg, s->get_reg(s, reg, mask));
}
static esp_err_t stream_handler(httpd_req_t *req) {
camera_fb_t *fb = NULL;
esp_err_t res = ESP_OK;
size_t _jpg_buf_len = 0;
uint8_t *_jpg_buf = NULL;
char *part_buf[64];
res = httpd_resp_set_type(req, _STREAM_CONTENT_TYPE);
if (res != ESP_OK) {
return res;
}
httpd_resp_set_hdr(req, "Access-Control-Allow-Origin", "*");
httpd_resp_set_hdr(req, "X-Framerate", "60");
while (true) {
fb = esp_camera_fb_get();
if (!fb) {
ESP_LOGE(TAG, "Camera capture failed");
res = ESP_FAIL;
} else {
if (fb->format != PIXFORMAT_JPEG) {
bool jpeg_converted = frame2jpg(fb, 80, &_jpg_buf, &_jpg_buf_len);
esp_camera_fb_return(fb);
fb = NULL;
if (!jpeg_converted) {
ESP_LOGE(TAG, "JPEG compression failed");
res = ESP_FAIL;
}
} else {
_jpg_buf_len = fb->len;
_jpg_buf = fb->buf;
}
}
if (res == ESP_OK) {
res = httpd_resp_send_chunk(req, _STREAM_BOUNDARY, strlen(_STREAM_BOUNDARY));
}
if (res == ESP_OK) {
size_t hlen = snprintf((char *)part_buf, 64, _STREAM_PART, _jpg_buf_len);
res = httpd_resp_send_chunk(req, (const char *)part_buf, hlen);
}
if (res == ESP_OK) {
res = httpd_resp_send_chunk(req, (const char *)_jpg_buf, _jpg_buf_len);
}
if (fb) {
esp_camera_fb_return(fb);
fb = NULL;
_jpg_buf = NULL;
} else if (_jpg_buf) {
free(_jpg_buf);
_jpg_buf = NULL;
}
if (res != ESP_OK) {
ESP_LOGE(TAG, "Send frame failed");
break;
}
}
return res;
}
static esp_err_t status_handler(httpd_req_t *req) {
static char json_response[1024];
sensor_t *s = esp_camera_sensor_get();
char *p = json_response;
*p++ = '{';
if (s->id.PID == OV5640_PID || s->id.PID == OV3660_PID) {
for (int reg = 0x3400; reg < 0x3406; reg += 2) {
p += print_reg(p, s, reg, 0xFFF); //12 bit
}
p += print_reg(p, s, 0x3406, 0xFF);
p += print_reg(p, s, 0x3500, 0xFFFF0); //16 bit
p += print_reg(p, s, 0x3503, 0xFF);
p += print_reg(p, s, 0x350a, 0x3FF); //10 bit
p += print_reg(p, s, 0x350c, 0xFFFF); //16 bit
for (int reg = 0x5480; reg <= 0x5490; reg++) {
p += print_reg(p, s, reg, 0xFF);
}
for (int reg = 0x5380; reg <= 0x538b; reg++) {
p += print_reg(p, s, reg, 0xFF);
}
for (int reg = 0x5580; reg < 0x558a; reg++) {
p += print_reg(p, s, reg, 0xFF);
}
p += print_reg(p, s, 0x558a, 0x1FF); //9 bit
} else if (s->id.PID == OV2640_PID) {
p += print_reg(p, s, 0xd3, 0xFF);
p += print_reg(p, s, 0x111, 0xFF);
p += print_reg(p, s, 0x132, 0xFF);
}
p += sprintf(p, "\"xclk\":%u,", s->xclk_freq_hz / 1000000);
p += sprintf(p, "\"pixformat\":%u,", s->pixformat);
p += sprintf(p, "\"framesize\":%u,", s->status.framesize);
p += sprintf(p, "\"quality\":%u,", s->status.quality);
p += sprintf(p, "\"brightness\":%d,", s->status.brightness);
p += sprintf(p, "\"contrast\":%d,", s->status.contrast);
p += sprintf(p, "\"saturation\":%d,", s->status.saturation);
p += sprintf(p, "\"sharpness\":%d,", s->status.sharpness);
p += sprintf(p, "\"special_effect\":%u,", s->status.special_effect);
p += sprintf(p, "\"wb_mode\":%u,", s->status.wb_mode);
p += sprintf(p, "\"awb\":%u,", s->status.awb);
p += sprintf(p, "\"awb_gain\":%u,", s->status.awb_gain);
p += sprintf(p, "\"aec\":%u,", s->status.aec);
p += sprintf(p, "\"aec2\":%u,", s->status.aec2);
p += sprintf(p, "\"ae_level\":%d,", s->status.ae_level);
p += sprintf(p, "\"aec_value\":%u,", s->status.aec_value);
p += sprintf(p, "\"agc\":%u,", s->status.agc);
p += sprintf(p, "\"agc_gain\":%u,", s->status.agc_gain);
p += sprintf(p, "\"gainceiling\":%u,", s->status.gainceiling);
p += sprintf(p, "\"bpc\":%u,", s->status.bpc);
p += sprintf(p, "\"wpc\":%u,", s->status.wpc);
p += sprintf(p, "\"raw_gma\":%u,", s->status.raw_gma);
p += sprintf(p, "\"lenc\":%u,", s->status.lenc);
p += sprintf(p, "\"hmirror\":%u,", s->status.hmirror);
p += sprintf(p, "\"dcw\":%u,", s->status.dcw);
p += sprintf(p, "\"colorbar\":%u", s->status.colorbar);
*p++ = '}';
*p++ = 0;
httpd_resp_set_type(req, "application/json");
httpd_resp_set_hdr(req, "Access-Control-Allow-Origin", "*");
return httpd_resp_send(req, json_response, strlen(json_response));
}
static esp_err_t cmd_handler(httpd_req_t *req) {
char *buf = NULL;
char variable[32];
char value[32];
if (parse_get(req, &buf) != ESP_OK) {
return ESP_FAIL;
}
if (httpd_query_key_value(buf, "var", variable, sizeof(variable)) != ESP_OK || httpd_query_key_value(buf, "val", value, sizeof(value)) != ESP_OK) {
free(buf);
httpd_resp_send_404(req);
return ESP_FAIL;
}
free(buf);
int val = atoi(value);
ESP_LOGI(TAG, "%s = %d", variable, val);
sensor_t *s = esp_camera_sensor_get();
int res = 0;
if (!strcmp(variable, "framesize")) {
if (s->pixformat == PIXFORMAT_JPEG) {
res = s->set_framesize(s, (framesize_t)val);
}
} else if (!strcmp(variable, "quality"))
res = s->set_quality(s, val);
else if (!strcmp(variable, "contrast"))
res = s->set_contrast(s, val);
else if (!strcmp(variable, "brightness"))
res = s->set_brightness(s, val);
else if (!strcmp(variable, "saturation"))
res = s->set_saturation(s, val);
else if (!strcmp(variable, "gainceiling"))
res = s->set_gainceiling(s, (gainceiling_t)val);
else if (!strcmp(variable, "colorbar"))
res = s->set_colorbar(s, val);
else if (!strcmp(variable, "awb"))
res = s->set_whitebal(s, val);
else if (!strcmp(variable, "agc"))
res = s->set_gain_ctrl(s, val);
else if (!strcmp(variable, "aec"))
res = s->set_exposure_ctrl(s, val);
else if (!strcmp(variable, "hmirror"))
res = s->set_hmirror(s, val);
else if (!strcmp(variable, "vflip"))
res = s->set_vflip(s, val);
else if (!strcmp(variable, "awb_gain"))
res = s->set_awb_gain(s, val);
else if (!strcmp(variable, "agc_gain"))
res = s->set_agc_gain(s, val);
else if (!strcmp(variable, "aec_value"))
res = s->set_aec_value(s, val);
else if (!strcmp(variable, "aec2"))
res = s->set_aec2(s, val);
else if (!strcmp(variable, "dcw"))
res = s->set_dcw(s, val);
else if (!strcmp(variable, "bpc"))
res = s->set_bpc(s, val);
else if (!strcmp(variable, "wpc"))
res = s->set_wpc(s, val);
else if (!strcmp(variable, "raw_gma"))
res = s->set_raw_gma(s, val);
else if (!strcmp(variable, "lenc"))
res = s->set_lenc(s, val);
else if (!strcmp(variable, "special_effect"))
res = s->set_special_effect(s, val);
else if (!strcmp(variable, "wb_mode"))
res = s->set_wb_mode(s, val);
else if (!strcmp(variable, "ae_level"))
res = s->set_ae_level(s, val);
else {
ESP_LOGI(TAG, "Unknown command: %s", variable);
res = -1;
}
if (res < 0) {
return httpd_resp_send_500(req);
}
httpd_resp_set_hdr(req, "Access-Control-Allow-Origin", "*");
return httpd_resp_send(req, NULL, 0);
}
static esp_err_t flash_handler(httpd_req_t *req) {
char *buf = NULL;
char _value[16];
if (parse_get(req, &buf) != ESP_OK) {
return ESP_FAIL;
}
if (
httpd_query_key_value(buf, "value", _value, sizeof(_value)) != ESP_OK
) {
free(buf);
httpd_resp_send_404(req);
return ESP_FAIL;
}
free(buf);
int flash = atoi(_value);
ESP_LOGW(TAG, "Set flash light %d", flash);
digitalWrite(PIN_FLASH, flash);
httpd_resp_set_hdr(req, "Access-Control-Allow-Origin", "*");
return httpd_resp_send(req, NULL, 0);
}
static esp_err_t servo_handler(httpd_req_t *req) {
return servoControl.handleRequest(req);
}
static esp_err_t navi_move_handler(httpd_req_t *req) {
return naviControl.handleMoveRequest(req);
}
static esp_err_t navi_stop_handler(httpd_req_t *req) {
return naviControl.handleStopRequest(req);
}
static httpd_uri_t get_uri(const char *uri, esp_err_t (*handler)(httpd_req_t *r)) {
return {
.uri = uri,
.method = HTTP_GET,
.handler = handler,
.user_ctx = NULL
};
}
void startCameraServer() {
httpd_config_t config = HTTPD_DEFAULT_CONFIG();
config.server_port = 80;
httpd_uri_t index_uri = get_uri("/", index_handler);
httpd_uri_t status_uri = get_uri("/status", status_handler);
httpd_uri_t cmd_uri = get_uri("/control", cmd_handler);
httpd_uri_t navi_move_uri = get_uri("/navi", navi_move_handler);
httpd_uri_t navi_stop_uri = get_uri("/stop", navi_stop_handler);
httpd_uri_t servo_uri = get_uri("/servo", servo_handler);
httpd_uri_t flash_uri = get_uri("/flash", flash_handler);
httpd_uri_t stream_uri = get_uri("/stream", stream_handler);
if (httpd_start(&server_httpd, &config) == ESP_OK) {
httpd_register_uri_handler(server_httpd, &index_uri);
httpd_register_uri_handler(server_httpd, &status_uri);
httpd_register_uri_handler(server_httpd, &cmd_uri);
httpd_register_uri_handler(server_httpd, &servo_uri);
httpd_register_uri_handler(server_httpd, &flash_uri);
httpd_register_uri_handler(server_httpd, &navi_move_uri);
httpd_register_uri_handler(server_httpd, &navi_stop_uri);
}
config.server_port += 1;
config.ctrl_port += 1;
if (httpd_start(&stream_httpd, &config) == ESP_OK) {
httpd_register_uri_handler(stream_httpd, &stream_uri);
}
}