Aktualizace na posledni lorol verzi

This commit is contained in:
Pavel Brychta 2021-02-27 18:58:53 +01:00
parent fe274c7e5e
commit da8025f886
27 changed files with 879 additions and 758 deletions

View File

@ -1,2 +1,3 @@
/*.js.gz
/*.gz
/edit_gz
/.exclude.files

Binary file not shown.

Binary file not shown.

View File

@ -166,7 +166,8 @@ float t = 0;
float h = 0;
bool udht = false;
bool heat_enabled_prev = false;
int ledState = LED_OFF;
bool ledState = LED_OFF;
bool ledOut = LED_OFF;
struct EE_bl {
byte memid; //here goes the EEMARK stamp
@ -180,7 +181,7 @@ struct EE_bl {
EE_bl ee = {0,0,0,0,0,0.1}; //populate as initial
// SUBS
void writeEE() {
void writeEE(){
ee.memid = EEMARK;
//EEPROM.put(EESC, sched); // only separately when needed with commit()
//EEPROM.put(EECH, memch); // not need to store and retrieve memch
@ -188,7 +189,7 @@ void writeEE() {
EEPROM.commit(); //needed for ESP8266?
}
void readEE() {
void readEE(){
byte ChkEE;
if (memch > MEMMAX) memch = 0;
EEPROM.get(EEBEGIN + memch*sizeof(ee), ChkEE);
@ -199,6 +200,20 @@ void readEE() {
}
}
void doOut(){
if (ledOut != ledState){ // only if changed
digitalWrite(ledPin, ledState); //consolidated here
ledOut = ledState; //update
if (ledState == LED_OFF){
ws.textAll("led,ledoff");
Serial.println(F("LED-OFF"));
} else {
ws.textAll("led,ledon");
Serial.println(F("LED-ON"));
}
}
}
void showTime()
{
byte tmpch = 0;
@ -208,13 +223,13 @@ void showTime()
now = time(nullptr);
const tm* tm = localtime(&now);
ws.printfAll("Now,Clock,%02d:%02d,%d", tm->tm_hour, tm->tm_min, tm->tm_wday);
if ((2==tm->tm_hour )&&(2==tm->tm_min)) {
if ((2==tm->tm_hour )&&(2==tm->tm_min)){
configTzTime(MYTZ, "pool.ntp.org");
Serial.print(F("Sync Clock at 02:02\n"));
}
Serial.printf("RTC: %02d:%02d\n", tm->tm_hour, tm->tm_min);
if (sched == 0) { // automatic
if (sched == 0){ // automatic
if ((tm->tm_wday > 0)&&(tm->tm_wday < 6)) tmpch = 0; //Mon - Fri
else if (tm->tm_wday == 6) tmpch = 1; //Sat
else if (tm->tm_wday == 0) tmpch = 2; //Sun
@ -222,7 +237,7 @@ void showTime()
tmpch = sched - 1; //and stays
}
if (tmpch != memch) { // update if different
if (tmpch != memch){ // update if different
memch = tmpch;
readEE();
ws.printfAll("Now,Setting,%02d:%02d,%02d:%02d,%+2.1f", ee.hstart, ee.mstart, ee.hstop, ee.mstop, ee.tempe);
@ -237,20 +252,18 @@ void showTime()
else { //enable smart if different
if (((bmi < emi)&&(bmi <= xmi)&&(xmi < emi))||
((emi < bmi)&&((bmi <= xmi)||(xmi < emi)))) {
((emi < bmi)&&((bmi <= xmi)||(xmi < emi)))){
heat_enabled = true;
} else heat_enabled = false;
}
if (heat_enabled_prev) { // smart control (delayed one cycle)
if (((t - HYST) < ee.tempe)&&(ledState == LED_OFF)) { // OFF->ON once
if (heat_enabled_prev){ // smart control (delayed one cycle)
if (((t + HYST) < ee.tempe)&&(ledState == LED_OFF)){ // OFF->ON once
ledState = LED_ON;
digitalWrite(ledPin, ledState); // apply change
ws.textAll("led,ledon");
}
if ((((t + HYST) > ee.tempe)&&(ledState == LED_ON))||(!heat_enabled)) { // ON->OFF once, also turn off at end of period.
if ((((t - HYST) > ee.tempe)&&(ledState == LED_ON))||(!heat_enabled)){ // ->OFF
ledState = LED_OFF;
digitalWrite(ledPin, ledState); // apply change
ws.textAll("led,ledoff");
}
@ -263,7 +276,7 @@ void showTime()
void updateDHT(){
float h1 = dht.readHumidity();
float t1 = dht.readTemperature(); //Celsius or dht.readTemperature(true) for Fahrenheit
if (isnan(h1) || isnan(t1)) {
if (isnan(h1) || isnan(t1)){
Serial.println(F("Failed to read from DHT sensor!"));
} else {
h = h1 + DHT_H_CORR;
@ -279,17 +292,9 @@ void analogSample()
void checkPhysicalButton()
{
if (digitalRead(btnPin) == LOW) {
if (btnState != LOW) { // btnState is used to avoid sequential toggles
if (digitalRead(btnPin) == LOW){
if (btnState != LOW){ // btnState is used to avoid sequential toggles
ledState = !ledState;
digitalWrite(ledPin, ledState);
if (ledState == LED_OFF) {
ws.textAll("led,ledoff");
Serial.println(F("LED-OFF"));
} else {
ws.textAll("led,ledon");
Serial.println(F("LED-ON"));
}
}
btnState = LOW;
} else {
@ -297,17 +302,17 @@ void checkPhysicalButton()
}
}
void mytimer() {
void mytimer(){
++count; //200ms increments
checkPhysicalButton();
if ((count % 25) == 1) { // update temp every 5 seconds
if ((count % 25) == 1){ // update temp every 5 seconds
analogSample();
udht = true;
}
if ((count % 50) == 0) { // update temp every 10 seconds
if ((count % 50) == 0){ // update temp every 10 seconds
ws.cleanupClients();
}
if (count >= 150) { // cycle every 30 sec
if (count >= 150){ // cycle every 30 sec
showTime();
count = 0;
}
@ -385,22 +390,21 @@ void onWsEvent(AsyncWebSocket * server, AsyncWebSocketClient * client, AwsEventT
Serial.printf("ws[%s][%u] %s-message[%llu]: ", server->url(), client->id(), (info->opcode == WS_TEXT)?"text":"binary", info->len);
if(info->opcode == WS_TEXT){
for(size_t i=0; i < info->len; i++) { //debug
for(size_t i=0; i < info->len; i++){ //debug
msg += (char) data[i];
}
if(data[0] == 'L') { // LED
if(data[1] == '1') {
if(data[0] == 'L'){ // LED
if(data[1] == '1'){
ledState = LED_ON;
ws.textAll("led,ledon"); // for others
}
else if(data[1] == '0') {
else if(data[1] == '0'){
ledState = LED_OFF;
ws.textAll("led,ledoff");
}
digitalWrite(ledPin, ledState); // apply change
} else if(data[0] == 'T') { // timeset
if (len > 11) {
} else if(data[0] == 'T'){ // timeset
if (len > 11){
data[3] = data[6] = data[9] = data[12] = 0; // cut strings
ee.hstart = (uint8_t) atoi((const char *) &data[1]);
ee.mstart = (uint8_t) atoi((const char *) &data[4]);
@ -411,8 +415,8 @@ void onWsEvent(AsyncWebSocket * server, AsyncWebSocketClient * client, AwsEventT
memch = 255; // to force showTime()to send Setting
showTime();
}
} else if(data[0] == 'W') { // temperatureset
if (len > 3) {
} else if(data[0] == 'W'){ // temperatureset
if (len > 3){
if (ee.tempe != (float) atof((const char *) &data[1])){
ee.tempe = (float) atof((const char *) &data[1]);
Serial.printf("[%u] Temp set %+2.1f\n", client->id(), ee.tempe);
@ -421,7 +425,7 @@ void onWsEvent(AsyncWebSocket * server, AsyncWebSocketClient * client, AwsEventT
showTime();
}
}
} else if ((data[0] == 'Z')&&(len > 2)) { // sched
} else if ((data[0] == 'Z')&&(len > 2)){ // sched
data[2] = 0;
if (sched != (uint8_t) atoi((const char *) &data[1])){
sched = (uint8_t) atoi((const char *) &data[1]);
@ -434,7 +438,7 @@ void onWsEvent(AsyncWebSocket * server, AsyncWebSocketClient * client, AwsEventT
} else {
char buff[3];
for(size_t i=0; i < info->len; i++) {
for(size_t i=0; i < info->len; i++){
sprintf(buff, "%02x ", (uint8_t) data[i]);
msg += buff ;
}
@ -457,12 +461,12 @@ void onWsEvent(AsyncWebSocket * server, AsyncWebSocketClient * client, AwsEventT
Serial.printf("ws[%s][%u] frame[%u] %s[%llu - %llu]: ", server->url(), client->id(), info->num, (info->message_opcode == WS_TEXT)?"text":"binary", info->index, info->index + len);
if(info->opcode == WS_TEXT){
for(size_t i=0; i < len; i++) {
for(size_t i=0; i < len; i++){
msg += (char) data[i];
}
} else {
char buff[3];
for(size_t i=0; i < len; i++) {
for(size_t i=0; i < len; i++){
sprintf(buff, "%02x ", (uint8_t) data[i]);
msg += buff ;
}
@ -488,7 +492,7 @@ void onWsEvent(AsyncWebSocket * server, AsyncWebSocketClient * client, AwsEventT
void setup(){
Serial.begin(115200);
Serial.setDebugOutput(true);
//Serial.setDebugOutput(true);
//Wifi
#ifdef USE_WFM
@ -511,7 +515,7 @@ void setup(){
//WiFi.softAP(hostName); // Core SVN 5179 use STA as default interface in mDNS (#7042)
WiFi.mode(WIFI_STA); // Core SVN 5179 use STA as default interface in mDNS (#7042)
WiFi.begin(ssid, password);
if (WiFi.waitForConnectResult() != WL_CONNECTED) {
if (WiFi.waitForConnectResult() != WL_CONNECTED){
Serial.print(F("STA: Failed!\n"));
WiFi.disconnect(false);
delay(1000);
@ -545,15 +549,14 @@ void setup(){
EEPROM.begin(EEALL);
//EEPROM.get(EECH, memch); //current channel, no need
readEE(); // populate structure if healthy
digitalWrite(ledPin, ledState);
Serial.printf("Timer set %02d:%02d - %02d:%02d\n", ee.hstart, ee.mstart, ee.hstop, ee.mstop);
Serial.printf("Temp set %+2.1f\n", ee.tempe);
//FS
#ifdef USE_FatFS
if (MYFS.begin(false,"/ffat",3)) { //limit the RAM usage, bottom line 8kb + 4kb takes per each file, default is 10
if (MYFS.begin(false,"/ffat",3)){ //limit the RAM usage, bottom line 8kb + 4kb takes per each file, default is 10
#else
if (MYFS.begin()) {
if (MYFS.begin()){
#endif
Serial.print(F("FS mounted\n"));
} else {
@ -654,7 +657,7 @@ void setup(){
#ifdef USE_AUTH_STAT
if(!request->authenticate(http_username, http_password)) return request->requestAuthentication();
#endif
request->onDisconnect([]() {
request->onDisconnect([](){
#ifdef ESP32
ESP.restart();
#elif defined(ESP8266)
@ -672,11 +675,23 @@ void setup(){
#ifdef USE_AUTH_STAT
if(!request->authenticate(http_username, http_password)) return request->requestAuthentication();
#endif
request->onDisconnect([]() {
WiFi.disconnect(true);
request->onDisconnect([](){
#ifdef ESP32
/*
//https://github.com/espressif/arduino-esp32/issues/400#issuecomment-499631249
//WiFi.disconnect(true); // doesn't work on esp32, below needs #include "esp_wifi.h"
wifi_init_config_t cfg = WIFI_INIT_CONFIG_DEFAULT(); //load the flash-saved configs
esp_wifi_init(&cfg); //initiate and allocate wifi resources (does not matter if connection fails)
if(esp_wifi_restore()!=ESP_OK){
Serial.print(F("WiFi is not initialized by esp_wifi_init "));
} else {
Serial.print(F("WiFi Configurations Cleared!"));
}
*/
WiFi.disconnect(true, true); // Works on esp32
ESP.restart();
#elif defined(ESP8266)
WiFi.disconnect(true);
ESP.reset();
#endif
});
@ -714,7 +729,7 @@ void setup(){
//OTA
ArduinoOTA.setHostname(hostName);
ArduinoOTA.onStart([]() {
ArduinoOTA.onStart([](){
Serial.print(F("OTA Started ...\n"));
MYFS.end(); // Clean FS
ws.textAll("Now,OTA"); // for all clients
@ -730,5 +745,6 @@ void loop(){
updateDHT();
udht = false;
}
doOut();
ArduinoOTA.handle();
}

View File

@ -1,2 +1,3 @@
/*.gz
/edit_gz
/.exclude.files

Binary file not shown.

Binary file not shown.

View File

@ -17,6 +17,9 @@ until a } is found on separate new line.
``` npm install html-minifier-terser -g, npm install -g github-files-fetcher ```
### Batch files provided
- **do.bat:** Generates **edit.htm.gz.h** file
- **do_emb.bat:** Generates **edit.htm.gz.h** file for embedding to **SPIFFSEditor.cpp** as binary C array -
You need to comment **#define EDFS** at **SPIFFSEditor.cpp** for this choice
- **do_ed_fs.bat:** Alternatively, makes a gzip-ed **edit.htm** file for fs -
uncomment **#define EDFS** for this choice. Saves about 4k of program flash storage.
- **undo.bat:** Reverts **edit.htm** from C array header to file (still minified!)
- **update_ace.bat:** Updates **acefull.js.gz** file from latest GitHub Ace sources

9
extras/do_ed_fs.bat Normal file
View File

@ -0,0 +1,9 @@
copy ..\src\edit.htm edit_src.htm
call html-minifier-terser --collapse-whitespace --remove-comments --remove-optional-tags --remove-redundant-attributes --remove-script-type-attributes --minify-css true --minify-js true -o edit.htm edit_src.htm
"C:\Program Files\7-Zip\7z.exe" a -tgzip -mx9 edit.htm.gz edit.htm
copy edit.htm.gz ..\examples\SmartSwitch\data\edit_gz
copy edit.htm.gz ..\examples\ESP_AsyncFSBrowser\data\edit_gz
ehg edit.htm.gz PROGMEM
copy edit.htm.gz.h ..\src\edit.htm.gz.h
pause
del edit.htm edit.htm.gz edit.htm.gz.h edit_src.htm

View File

@ -1,6 +1,8 @@
copy ..\src\edit.htm edit_src.htm
call html-minifier-terser --collapse-whitespace --remove-comments --remove-optional-tags --remove-redundant-attributes --remove-script-type-attributes --minify-css true --minify-js true -o edit.htm edit_src.htm
"C:\Program Files\7-Zip\7z.exe" a -tgzip -mx9 edit.htm.gz edit.htm
del ..\examples\SmartSwitch\data\edit.htm
del ..\examples\ESP_AsyncFSBrowser\data\edit.htm
ehg edit.htm.gz PROGMEM
copy edit.htm.gz.h ..\src\edit.htm.gz.h
pause

View File

@ -4,6 +4,7 @@ REM fetcher --url=resource_url --out=output_directory
call fetcher --url="https://github.com/ajaxorg/ace-builds/blob/master/src-min-noconflict/ace.js" --out=tmp1
call fetcher --url="https://github.com/ajaxorg/ace-builds/blob/master/src-min-noconflict/mode-html.js" --out=tmp1
call fetcher --url="https://github.com/ajaxorg/ace-builds/blob/master/src-min-noconflict/mode-json.js" --out=tmp1
call fetcher --url="https://github.com/ajaxorg/ace-builds/blob/master/src-min-noconflict/theme-monokai.js" --out=tmp1
call fetcher --url="https://github.com/ajaxorg/ace-builds/blob/master/src-min-noconflict/ext-searchbox.js" --out=tmp1
@ -12,12 +13,14 @@ REM and do not take and include them below
call fetcher --url="https://github.com/ajaxorg/ace-builds/blob/master/src-min-noconflict/worker-html.js" --out=tmp1
call fetcher --url="https://github.com/ajaxorg/ace-builds/blob/master/src-min-noconflict/worker-css.js" --out=tmp1
call fetcher --url="https://github.com/ajaxorg/ace-builds/blob/master/src-min-noconflict/worker-javascript.js" --out=tmp1
call fetcher --url="https://github.com/ajaxorg/ace-builds/blob/master/src-min-noconflict/worker-json.js" --out=tmp1
cd tmp1
type ace.js mode-html.js theme-monokai.js ext-searchbox.js > acefull.js
type ace.js mode-html.js mode-json.js theme-monokai.js ext-searchbox.js > acefull.js
"C:\Program Files\7-Zip\7z.exe" a -tgzip -mx9 acefull.js.gz acefull.js
"C:\Program Files\7-Zip\7z.exe" a -tgzip -mx9 worker-html.js.gz worker-html.js
"C:\Program Files\7-Zip\7z.exe" a -tgzip -mx9 worker-javascript.js.gz worker-javascript.js
"C:\Program Files\7-Zip\7z.exe" a -tgzip -mx9 worker-json.js.gz worker-json.js
"C:\Program Files\7-Zip\7z.exe" a -tgzip -mx9 worker-css.js.gz worker-css.js
REM update SmartSwitch /data:
@ -25,6 +28,7 @@ pause
copy acefull.js.gz ..\..\examples\SmartSwitch\data\acefull.js.gz
copy worker-html.js.gz ..\..\examples\SmartSwitch\data\worker-html.js.gz
copy worker-javascript.js.gz ..\..\examples\SmartSwitch\data\worker-javascript.js.gz
copy worker-json.js.gz ..\..\examples\SmartSwitch\data\worker-json.js.gz
copy worker-css.js.gz ..\..\examples\SmartSwitch\data\worker-css.js.gz
REM update ESP_AsyncFSBrowser /data:
@ -32,6 +36,7 @@ pause
copy acefull.js.gz ..\..\examples\ESP_AsyncFSBrowser\data\acefull.js.gz
copy worker-html.js.gz ..\..\examples\ESP_AsyncFSBrowser\data\worker-html.js.gz
copy worker-javascript.js.gz ..\..\examples\ESP_AsyncFSBrowser\data\worker-javascript.js.gz
copy worker-json.js.gz ..\..\examples\ESP_AsyncFSBrowser\data\worker-json.js.gz
copy worker-css.js.gz ..\..\examples\ESP_AsyncFSBrowser\data\worker-css.js.gz
REM delete temporary stuff

View File

@ -52,11 +52,15 @@ size_t webSocketSendFrameWindow(AsyncClient *client){
}
size_t webSocketSendFrame(AsyncClient *client, bool final, uint8_t opcode, bool mask, uint8_t *data, size_t len){
if(!client->canSend())
if(!client->canSend()) {
// Serial.println("SF 1");
return 0;
}
size_t space = client->space();
if(space < 2)
if(space < 2) {
// Serial.println("SF 2");
return 0;
}
uint8_t mbuf[4] = {0,0,0,0};
uint8_t headLen = 2;
if(len && mask){
@ -68,8 +72,10 @@ size_t webSocketSendFrame(AsyncClient *client, bool final, uint8_t opcode, bool
}
if(len > 125)
headLen += 2;
if(space < headLen)
if(space < headLen) {
// Serial.println("SF 2");
return 0;
}
space -= headLen;
if(len > space) len = space;
@ -77,6 +83,7 @@ size_t webSocketSendFrame(AsyncClient *client, bool final, uint8_t opcode, bool
uint8_t *buf = (uint8_t*)malloc(headLen);
if(buf == NULL){
//os_printf("could not malloc %u bytes for frame header\n", headLen);
// Serial.println("SF 3");
return 0;
}
@ -97,6 +104,7 @@ size_t webSocketSendFrame(AsyncClient *client, bool final, uint8_t opcode, bool
if(client->add((const char *)buf, headLen) != headLen){
//os_printf("error adding %lu header bytes\n", headLen);
free(buf);
// Serial.println("SF 4");
return 0;
}
free(buf);
@ -109,13 +117,16 @@ size_t webSocketSendFrame(AsyncClient *client, bool final, uint8_t opcode, bool
}
if(client->add((const char *)data, len) != len){
//os_printf("error adding %lu data bytes\n", len);
// Serial.println("SF 5");
return 0;
}
}
if(!client->send()){
//os_printf("error sending frame: %lu\n", headLen+len);
// Serial.println("SF 6");
return 0;
}
// Serial.println("SF");
return len;
}
@ -149,6 +160,7 @@ AsyncWebSocketMessageBuffer::AsyncWebSocketMessageBuffer(uint8_t * data, size_t
_data = new uint8_t[_len + 1];
if (_data) {
// Serial.println("BUFF alloc");
memcpy(_data, data, _len);
_data[_len] = 0;
}
@ -164,6 +176,7 @@ AsyncWebSocketMessageBuffer::AsyncWebSocketMessageBuffer(size_t size)
_data = new uint8_t[_len + 1];
if (_data) {
// Serial.println("BUFF alloc");
_data[_len] = 0;
}
@ -185,6 +198,7 @@ AsyncWebSocketMessageBuffer::AsyncWebSocketMessageBuffer(const AsyncWebSocketMes
}
if (_data) {
// Serial.println("BUFF alloc");
memcpy(_data, copy._data, _len);
_data[_len] = 0;
}
@ -202,6 +216,7 @@ AsyncWebSocketMessageBuffer::AsyncWebSocketMessageBuffer(AsyncWebSocketMessageBu
_count = 0;
if (copy._data) {
// Serial.println("BUFF alloc");
_data = copy._data;
copy._data = nullptr;
}
@ -211,6 +226,7 @@ AsyncWebSocketMessageBuffer::AsyncWebSocketMessageBuffer(AsyncWebSocketMessageBu
AsyncWebSocketMessageBuffer::~AsyncWebSocketMessageBuffer()
{
if (_data) {
// Serial.println("BUFF free");
delete[] _data;
}
}
@ -293,6 +309,7 @@ AsyncWebSocketBasicMessage::AsyncWebSocketBasicMessage(const char * data, size_t
_opcode = opcode & 0x07;
_mask = mask;
_data = (uint8_t*)malloc(_len+1);
// Serial.println("MSG alloc");
if(_data == NULL){
_len = 0;
_status = WS_MSG_ERROR;
@ -316,35 +333,43 @@ AsyncWebSocketBasicMessage::AsyncWebSocketBasicMessage(uint8_t opcode, bool mask
AsyncWebSocketBasicMessage::~AsyncWebSocketBasicMessage() {
if(_data != NULL)
if(_data != NULL) {
// Serial.println("MSG free");
free(_data);
}
}
void AsyncWebSocketBasicMessage::ack(size_t len, uint32_t time) {
(void)time;
_acked += len;
// Serial.printf("ACK %u = %u | %u = %u\n", _sent, _len, _acked, _ack);
if(_sent == _len && _acked == _ack){
// Serial.println("ACK end");
_status = WS_MSG_SENT;
}
}
size_t AsyncWebSocketBasicMessage::send(AsyncClient *client) {
if(_status != WS_MSG_SENDING)
if(_status != WS_MSG_SENDING){
// Serial.println("MS 1");
return 0;
}
if(_acked < _ack){
// Serial.println("MS 2");
return 0;
}
if(_sent == _len){
if(_acked == _ack)
_status = WS_MSG_SENT;
// Serial.println("MS 3");
_status = WS_MSG_SENT;
return 0;
}
if(_sent > _len){
// Serial.println("MS 4");
_status = WS_MSG_ERROR;
return 0;
}
size_t toSend = _len - _sent;
size_t window = webSocketSendFrameWindow(client);
// Serial.printf("Send %u %u %u\n", _len, _sent, toSend);
if(window < toSend) {
toSend = window;
@ -360,8 +385,14 @@ AsyncWebSocketBasicMessage::~AsyncWebSocketBasicMessage() {
size_t sent = webSocketSendFrame(client, final, opCode, _mask, dPtr, toSend);
_status = WS_MSG_SENDING;
if(toSend && sent != toSend){
_sent -= (toSend - sent);
_ack -= (toSend - sent);
size_t delta = (toSend - sent);
// Serial.printf("\ns:%u a:%u d:%u\n", _sent, _ack, delta);
_sent -= delta;
_ack -= delta + ((delta < 126)?2:4) + (_mask * 4);
// Serial.printf("s:%u a:%u\n", _sent, _ack);
if (!sent) {
_status = WS_MSG_ERROR;
}
}
return sent;
}
@ -399,11 +430,13 @@ AsyncWebSocketMultiMessage::AsyncWebSocketMultiMessage(AsyncWebSocketMessageBuff
if (buffer) {
_WSbuffer = buffer;
(*_WSbuffer)++;
// Serial.printf("INC WSbuffer == %u\n", _WSbuffer->count());
_data = buffer->get();
_len = buffer->length();
_status = WS_MSG_SENDING;
//ets_printf("M: %u\n", _len);
} else {
// Serial.println("BUFF ERROR");
_status = WS_MSG_ERROR;
}
@ -413,40 +446,48 @@ AsyncWebSocketMultiMessage::AsyncWebSocketMultiMessage(AsyncWebSocketMessageBuff
AsyncWebSocketMultiMessage::~AsyncWebSocketMultiMessage() {
if (_WSbuffer) {
(*_WSbuffer)--; // decreases the counter.
// Serial.printf("DEC WSbuffer == %u\n", _WSbuffer->count());
}
}
void AsyncWebSocketMultiMessage::ack(size_t len, uint32_t time) {
(void)time;
_acked += len;
// Serial.printf("ACK %u = %u | %u = %u\n", _sent, _len, _acked, _ack);
if(_sent >= _len && _acked >= _ack){
// Serial.println("ACK end");
_status = WS_MSG_SENT;
}
//ets_printf("A: %u\n", len);
}
size_t AsyncWebSocketMultiMessage::send(AsyncClient *client) {
if(_status != WS_MSG_SENDING)
if(_status != WS_MSG_SENDING) {
// Serial.println("MS 1");
return 0;
}
if(_acked < _ack){
// Serial.println("MS 2");
return 0;
}
if(_sent == _len){
// Serial.println("MS 3");
_status = WS_MSG_SENT;
return 0;
}
if(_sent > _len){
// Serial.println("MS 4");
_status = WS_MSG_ERROR;
//ets_printf("E: %u > %u\n", _sent, _len);
return 0;
}
size_t toSend = _len - _sent;
size_t window = webSocketSendFrameWindow(client);
// Serial.printf("Send %u %u %u\n", _len, _sent, toSend);
if(window < toSend) {
toSend = window;
}
// Serial.printf("s:%u a:%u t:%u\n", _sent, _ack, toSend);
_sent += toSend;
_ack += toSend + ((toSend < 126)?2:4) + (_mask * 4);
@ -460,8 +501,14 @@ AsyncWebSocketMultiMessage::~AsyncWebSocketMultiMessage() {
_status = WS_MSG_SENDING;
if(toSend && sent != toSend){
//ets_printf("E: %u != %u\n", toSend, sent);
_sent -= (toSend - sent);
_ack -= (toSend - sent);
size_t delta = (toSend - sent);
// Serial.printf("\ns:%u a:%u d:%u\n", _sent, _ack, delta);
_sent -= delta;
_ack -= delta + ((delta < 126)?2:4) + (_mask * 4);
// Serial.printf("s:%u a:%u\n", _sent, _ack);
if (!sent) {
_status = WS_MSG_ERROR;
}
}
//ets_printf("S: %u %u\n", _sent, sent);
return sent;
@ -496,16 +543,25 @@ AsyncWebSocketClient::AsyncWebSocketClient(AsyncWebServerRequest *request, Async
_server->_addClient(this);
_server->_handleEvent(this, WS_EVT_CONNECT, request, NULL, 0);
delete request;
memset(&_pinfo,0,sizeof(_pinfo)); //
memset(&_pinfo,0,sizeof(_pinfo));
}
AsyncWebSocketClient::~AsyncWebSocketClient(){
// Serial.printf("%u FREE Q\n", id());
_messageQueue.free();
_controlQueue.free();
_server->_cleanBuffers();
_server->_handleEvent(this, WS_EVT_DISCONNECT, NULL, NULL, 0);
}
void AsyncWebSocketClient::_clearQueue(){
while(!_messageQueue.isEmpty() && _messageQueue.front()->finished()){
_messageQueue.remove(_messageQueue.front());
}
}
void AsyncWebSocketClient::_onAck(size_t len, uint32_t time){
// Serial.printf("%u onAck\n", id());
_lastMessageTime = millis();
if(!_controlQueue.isEmpty()){
auto head = _controlQueue.front();
@ -520,15 +576,21 @@ void AsyncWebSocketClient::_onAck(size_t len, uint32_t time){
_controlQueue.remove(head);
}
}
if(len && !_messageQueue.isEmpty()){
_messageQueue.front()->ack(len, time);
}
_clearQueue();
_server->_cleanBuffers();
// Serial.println("RUN 1");
_runQueue();
}
void AsyncWebSocketClient::_onPoll(){
if(_client->canSend() && (!_controlQueue.isEmpty() || !_messageQueue.isEmpty())){
// Serial.println("RUN 2");
_runQueue();
} else if(_keepAlivePeriod > 0 && _controlQueue.isEmpty() && _messageQueue.isEmpty() && (millis() - _lastMessageTime) >= _keepAlivePeriod){
ping((uint8_t *)AWSC_PING_PAYLOAD, AWSC_PING_PAYLOAD_LEN);
@ -536,15 +598,20 @@ void AsyncWebSocketClient::_onPoll(){
}
void AsyncWebSocketClient::_runQueue(){
while(!_messageQueue.isEmpty() && _messageQueue.front()->finished()){
_messageQueue.remove(_messageQueue.front());
}
_clearQueue();
//size_t m0 = _messageQueue.isEmpty()? 0 : _messageQueue.length();
//size_t m1 = _messageQueue.isEmpty()? 0 : _messageQueue.front()->betweenFrames();
// Serial.printf("%u R C = %u %u\n", _clientId, m0, m1);
if(!_controlQueue.isEmpty() && (_messageQueue.isEmpty() || _messageQueue.front()->betweenFrames()) && webSocketSendFrameWindow(_client) > (size_t)(_controlQueue.front()->len() - 1)){
// Serial.printf("%u R S C\n", _clientId);
_controlQueue.front()->send(_client);
} else if(!_messageQueue.isEmpty() && _messageQueue.front()->betweenFrames() && webSocketSendFrameWindow(_client)){
// Serial.printf("%u R S M = ", _clientId);
_messageQueue.front()->send(_client);
}
_clearQueue();
}
bool AsyncWebSocketClient::queueIsFull(){
@ -553,28 +620,38 @@ bool AsyncWebSocketClient::queueIsFull(){
}
void AsyncWebSocketClient::_queueMessage(AsyncWebSocketMessage *dataMessage){
if(dataMessage == NULL)
if(dataMessage == NULL){
// Serial.printf("%u Q1\n", _clientId);
return;
}
if(_status != WS_CONNECTED){
// Serial.printf("%u Q2\n", _clientId);
delete dataMessage;
return;
}
if(_messageQueue.length() >= WS_MAX_QUEUED_MESSAGES){
ets_printf(String(F("ERROR: Too many messages queued\n")).c_str());
// Serial.printf("%u Q3\n", _clientId);
delete dataMessage;
} else {
_messageQueue.add(dataMessage);
// Serial.printf("%u Q A %u\n", _clientId, _messageQueue.length());
}
if(_client->canSend())
if(_client->canSend()) {
// Serial.printf("%u Q S\n", _clientId);
// Serial.println("RUN 3");
_runQueue();
}
}
void AsyncWebSocketClient::_queueControl(AsyncWebSocketControl *controlMessage){
if(controlMessage == NULL)
return;
_controlQueue.add(controlMessage);
if(_client->canSend())
if(_client->canSend()) {
// Serial.println("RUN 4");
_runQueue();
}
}
void AsyncWebSocketClient::close(uint16_t code, const char * message){
@ -607,19 +684,24 @@ void AsyncWebSocketClient::ping(uint8_t *data, size_t len){
_queueControl(new AsyncWebSocketControl(WS_PING, data, len));
}
void AsyncWebSocketClient::_onError(int8_t){}
void AsyncWebSocketClient::_onError(int8_t){
//Serial.println("onErr");
}
void AsyncWebSocketClient::_onTimeout(uint32_t time){
// Serial.println("onTime");
(void)time;
_client->close(true);
}
void AsyncWebSocketClient::_onDisconnect(){
// Serial.println("onDis");
_client = NULL;
_server->_handleDisconnect(this);
}
void AsyncWebSocketClient::_onData(void *pbuf, size_t plen){
// Serial.println("onData");
_lastMessageTime = millis();
uint8_t *data = (uint8_t*)pbuf;
while(plen > 0){
@ -664,9 +746,9 @@ void AsyncWebSocketClient::_onData(void *pbuf, size_t plen){
if(_pinfo.opcode){
_pinfo.message_opcode = _pinfo.opcode;
_pinfo.num = 0;
} else _pinfo.num += 1;
}
}
_server->_handleEvent(this, WS_EVT_DATA, (void *)&_pinfo, (uint8_t*)data, datalen);
if (datalen > 0) _server->_handleEvent(this, WS_EVT_DATA, (void *)&_pinfo, (uint8_t*)data, datalen);
_pinfo.index += datalen;
} else if((datalen + _pinfo.index) == _pinfo.len){
@ -694,6 +776,8 @@ void AsyncWebSocketClient::_onData(void *pbuf, size_t plen){
_server->_handleEvent(this, WS_EVT_PONG, NULL, data, datalen);
} else if(_pinfo.opcode < 8){//continuation or text/binary frame
_server->_handleEvent(this, WS_EVT_DATA, (void *)&_pinfo, data, datalen);
if (_pinfo.final) _pinfo.num = 0;
else _pinfo.num += 1;
}
} else {
//os_printf("frame error: len: %u, index: %llu, total: %llu\n", datalen, _pinfo.index, _pinfo.len);
@ -957,6 +1041,7 @@ void AsyncWebSocket::textAll(AsyncWebSocketMessageBuffer * buffer){
void AsyncWebSocket::textAll(const char * message, size_t len){
//if (_buffers.length()) return;
AsyncWebSocketMessageBuffer * WSBuffer = makeBuffer((uint8_t *)message, len);
textAll(WSBuffer);
}
@ -1229,6 +1314,7 @@ AsyncWebSocketMessageBuffer * AsyncWebSocket::makeBuffer(uint8_t * data, size_t
if (buffer) {
AsyncWebLockGuard l(_lock);
// Serial.printf("Add to global buffers = %u\n", _buffers.length() + 1);
_buffers.add(buffer);
}
@ -1238,9 +1324,9 @@ AsyncWebSocketMessageBuffer * AsyncWebSocket::makeBuffer(uint8_t * data, size_t
void AsyncWebSocket::_cleanBuffers()
{
AsyncWebLockGuard l(_lock);
for(AsyncWebSocketMessageBuffer * c: _buffers){
if(c && c->canDelete()){
// Serial.printf("Remove from global buffers = %u\n", _buffers.length() - 1);
_buffers.remove(c);
}
}

View File

@ -173,6 +173,7 @@ class AsyncWebSocketClient {
void _queueMessage(AsyncWebSocketMessage *dataMessage);
void _queueControl(AsyncWebSocketControl *controlMessage);
void _runQueue();
void _clearQueue();
public:
void *_tempObject;
@ -205,6 +206,7 @@ class AsyncWebSocketClient {
//data packets
void message(AsyncWebSocketMessage *message){ _queueMessage(message); }
bool queueIsFull();
size_t queueLen() { return _messageQueue.length() + _controlQueue.length(); }
size_t printf(const char *format, ...) __attribute__ ((format (printf, 2, 3)));
#ifndef ESP32

View File

@ -59,22 +59,14 @@ class AsyncResponseStream;
#ifndef WEBSERVER_H
typedef enum {
HTTP_GET = 0b0000000000000001,
HTTP_POST = 0b0000000000000010,
HTTP_DELETE = 0b0000000000000100,
HTTP_PUT = 0b0000000000001000,
HTTP_PATCH = 0b0000000000010000,
HTTP_HEAD = 0b0000000000100000,
HTTP_OPTIONS = 0b0000000001000000,
HTTP_PROPFIND = 0b0000000010000000,
HTTP_LOCK = 0b0000000100000000,
HTTP_UNLOCK = 0b0000001000000000,
HTTP_PROPPATCH = 0b0000010000000000,
HTTP_MKCOL = 0b0000100000000000,
HTTP_MOVE = 0b0001000000000000,
HTTP_COPY = 0b0010000000000000,
HTTP_RESERVED = 0b0100000000000000,
HTTP_ANY = 0b0111111111111111,
HTTP_GET = 0b00000001,
HTTP_POST = 0b00000010,
HTTP_DELETE = 0b00000100,
HTTP_PUT = 0b00001000,
HTTP_PATCH = 0b00010000,
HTTP_HEAD = 0b00100000,
HTTP_OPTIONS = 0b01000000,
HTTP_ANY = 0b01111111,
} WebRequestMethod;
#endif
@ -94,7 +86,7 @@ namespace fs {
//if this value is returned when asked for data, packet will not be sent and you will be asked for data again
#define RESPONSE_TRY_AGAIN 0xFFFFFFFF
typedef uint16_t WebRequestMethodComposite;
typedef uint8_t WebRequestMethodComposite;
typedef std::function<void(void)> ArDisconnectHandler;
/*

View File

@ -1,14 +1,18 @@
#include "SPIFFSEditor.h"
#include <FS.h>
#include "edit.htm.gz.h"
#define EDFS
#ifndef EDFS
#include "edit.htm.gz.h"
#endif
#ifdef ESP32
#define fullName(x) name(x)
#endif
#define SPIFFS_MAXLENGTH_FILEPATH 32
const char *excludeListFile = "/.exclude.files";
static const char excludeListFile[] PROGMEM = "/.exclude.files";
typedef struct ExcludeListS {
char *item;
@ -103,7 +107,7 @@ static void loadExcludeList(fs::FS &_fs, const char *filename){
static bool isExcluded(fs::FS &_fs, const char *filename) {
if(excludes == NULL){
loadExcludeList(_fs, excludeListFile);
loadExcludeList(_fs, String(FPSTR(excludeListFile)).c_str());
}
ExcludeList *e = excludes;
while(e){
@ -130,12 +134,12 @@ SPIFFSEditor::SPIFFSEditor(const String& username, const String& password, const
{}
bool SPIFFSEditor::canHandle(AsyncWebServerRequest *request){
if(request->url().equalsIgnoreCase("/edit")){
if(request->url().equalsIgnoreCase(F("/edit"))){
if(request->method() == HTTP_GET){
if(request->hasParam("list"))
if(request->hasParam(F("list")))
return true;
if(request->hasParam("edit")){
request->_tempFile = _fs.open(request->arg("edit"), "r");
if(request->hasParam(F("edit"))){
request->_tempFile = _fs.open(request->arg(F("edit")), "r");
if(!request->_tempFile){
return false;
}
@ -147,7 +151,7 @@ bool SPIFFSEditor::canHandle(AsyncWebServerRequest *request){
#endif
}
if(request->hasParam("download")){
request->_tempFile = _fs.open(request->arg("download"), "r");
request->_tempFile = _fs.open(request->arg(F("download")), "r");
if(!request->_tempFile){
return false;
}
@ -158,7 +162,7 @@ bool SPIFFSEditor::canHandle(AsyncWebServerRequest *request){
}
#endif
}
request->addInterestingHeader("If-Modified-Since");
request->addInterestingHeader(F("If-Modified-Since"));
return true;
}
else if(request->method() == HTTP_POST)
@ -178,8 +182,8 @@ void SPIFFSEditor::handleRequest(AsyncWebServerRequest *request){
return request->requestAuthentication();
if(request->method() == HTTP_GET){
if(request->hasParam("list")){
String path = request->getParam("list")->value();
if(request->hasParam(F("list"))){
String path = request->getParam(F("list"))->value();
#ifdef ESP32
File dir = _fs.open(path);
#else
@ -204,11 +208,11 @@ void SPIFFSEditor::handleRequest(AsyncWebServerRequest *request){
continue;
}
if (output != "[") output += ',';
output += "{\"type\":\"";
output += "file";
output += "\",\"name\":\"";
output += F("{\"type\":\"");
output += F("file");
output += F("\",\"name\":\"");
output += String(fname);
output += "\",\"size\":";
output += F("\",\"size\":");
output += String(entry.size());
output += "}";
#ifdef ESP32
@ -221,41 +225,44 @@ void SPIFFSEditor::handleRequest(AsyncWebServerRequest *request){
dir.close();
#endif
output += "]";
request->send(200, "application/json", output);
request->send(200, F("application/json"), output);
output = String();
}
else if(request->hasParam("edit") || request->hasParam("download")){
request->send(request->_tempFile, request->_tempFile.fullName(), String(), request->hasParam("download"));
else if(request->hasParam(F("edit")) || request->hasParam(F("download"))){
request->send(request->_tempFile, request->_tempFile.fullName(), String(), request->hasParam(F("download")));
}
else {
const char * buildTime = __DATE__ " " __TIME__ " GMT";
if (request->header("If-Modified-Since").equals(buildTime)) {
if (request->header(F("If-Modified-Since")).equals(buildTime)) {
request->send(304);
} else {
AsyncWebServerResponse *response = request->beginResponse_P(200, "text/html", edit_htm_gz, edit_htm_gz_len);
response->addHeader("Content-Encoding", "gzip");
response->addHeader("Last-Modified", buildTime);
request->send(response);
#ifdef EDFS
AsyncWebServerResponse *response = request->beginResponse(_fs, F("/edit_gz"), F("text/html"), false);
#else
AsyncWebServerResponse *response = request->beginResponse_P(200, F("text/html"), edit_htm_gz, edit_htm_gz_len);
#endif
response->addHeader(F("Content-Encoding"), F("gzip"));
response->addHeader(F("Last-Modified"), buildTime);
request->send(response);
}
}
} else if(request->method() == HTTP_DELETE){
if(request->hasParam("path", true)){
if(!(_fs.remove(request->getParam("path", true)->value()))){
if(request->hasParam(F("path"), true)){
if(!(_fs.remove(request->getParam(F("path"), true)->value()))){
#ifdef ESP32
_fs.rmdir(request->getParam("path", true)->value()); // try rmdir for littlefs
_fs.rmdir(request->getParam(F("path"), true)->value()); // try rmdir for littlefs
#endif
}
request->send(200, "", "DELETE: "+request->getParam("path", true)->value());
request->send(200, "", String(F("DELETE: "))+request->getParam(F("path"), true)->value());
} else
request->send(404);
} else if(request->method() == HTTP_POST){
if(request->hasParam("data", true, true) && _fs.exists(request->getParam("data", true, true)->value()))
request->send(200, "", "UPLOADED: "+request->getParam("data", true, true)->value());
if(request->hasParam(F("data"), true, true) && _fs.exists(request->getParam(F("data"), true, true)->value()))
request->send(200, "", String(F("UPLOADED: "))+request->getParam(F("data"), true, true)->value());
else if(request->hasParam("rawname", true) && request->hasParam("raw0", true)){
String rawnam = request->getParam("rawname", true)->value();
else if(request->hasParam(F("rawname"), true) && request->hasParam(F("raw0"), true)){
String rawnam = request->getParam(F("rawname"), true)->value();
if (_fs.exists(rawnam)) _fs.remove(rawnam); // delete it to allow a mode
@ -263,22 +270,22 @@ void SPIFFSEditor::handleRequest(AsyncWebServerRequest *request){
uint16_t i = 0;
fs::File f = _fs.open(rawnam, "a");
while (request->hasParam("raw" + String(k), true)) { //raw0 .. raw1
while (request->hasParam(String(F("raw")) + String(k), true)) { //raw0 .. raw1
if(f){
i += f.print(request->getParam("raw" + String(k), true)->value());
i += f.print(request->getParam(String(F("raw")) + String(k), true)->value());
}
k++;
}
f.close();
request->send(200, "", "IPADWRITE: " + rawnam + ":" + String(i));
request->send(200, "", String(F("IPADWRITE: ")) + rawnam + ":" + String(i));
} else {
request->send(500);
}
} else if(request->method() == HTTP_PUT){
if(request->hasParam("path", true)){
String filename = request->getParam("path", true)->value();
if(request->hasParam(F("path"), true)){
String filename = request->getParam(F("path"), true)->value();
if(_fs.exists(filename)){
request->send(200);
} else {
@ -306,7 +313,7 @@ void SPIFFSEditor::handleRequest(AsyncWebServerRequest *request){
if(f){
f.write((uint8_t)0x00);
f.close();
request->send(200, "", "CREATE: "+filename);
request->send(200, "", String(F("CREATE: "))+filename);
} else {
request->send(500);
}

View File

@ -105,6 +105,13 @@ class AsyncCallbackWebHandler: public AsyncWebHandler {
}
} else
#endif
if (_uri.length() && _uri.startsWith("/*.")) {
String uriTemplate = String (_uri);
uriTemplate = uriTemplate.substring(uriTemplate.lastIndexOf("."));
if (!request->url().endsWith(uriTemplate))
return false;
}
else
if (_uri.length() && _uri.endsWith("*")) {
String uriTemplate = String(_uri);
uriTemplate = uriTemplate.substring(0, uriTemplate.length() - 1);
@ -119,16 +126,22 @@ class AsyncCallbackWebHandler: public AsyncWebHandler {
}
virtual void handleRequest(AsyncWebServerRequest *request) override final {
if((_username != "" && _password != "") && !request->authenticate(_username.c_str(), _password.c_str()))
return request->requestAuthentication();
if(_onRequest)
_onRequest(request);
else
request->send(500);
}
virtual void handleUpload(AsyncWebServerRequest *request, const String& filename, size_t index, uint8_t *data, size_t len, bool final) override final {
if((_username != "" && _password != "") && !request->authenticate(_username.c_str(), _password.c_str()))
return request->requestAuthentication();
if(_onUpload)
_onUpload(request, filename, index, data, len, final);
}
virtual void handleBody(AsyncWebServerRequest *request, uint8_t *data, size_t len, size_t index, size_t total) override final {
if((_username != "" && _password != "") && !request->authenticate(_username.c_str(), _password.c_str()))
return request->requestAuthentication();
if(_onBody)
_onBody(request, data, len, index, total);
}

View File

@ -192,8 +192,16 @@ void AsyncWebServerRequest::_removeNotInterestingHeaders(){
void AsyncWebServerRequest::_onPoll(){
//os_printf("p\n");
if(_response != NULL && _client != NULL && _client->canSend() && !_response->_finished()){
_response->_ack(this, 0, 0);
if(_response != NULL && _client != NULL && _client->canSend()){
if(!_response->_finished()){
_response->_ack(this, 0, 0);
} else {
AsyncWebServerResponse* r = _response;
_response = NULL;
delete r;
_client->close();
}
}
}
@ -202,10 +210,12 @@ void AsyncWebServerRequest::_onAck(size_t len, uint32_t time){
if(_response != NULL){
if(!_response->_finished()){
_response->_ack(this, len, time);
} else {
} else if(_response->_finished()){
AsyncWebServerResponse* r = _response;
_response = NULL;
delete r;
_client->close();
}
}
}
@ -276,24 +286,6 @@ bool AsyncWebServerRequest::_parseReqHead(){
_method = HTTP_HEAD;
} else if(m == F("OPTIONS")){
_method = HTTP_OPTIONS;
} else if(m == F("PROPFIND")){
_method = HTTP_PROPFIND;
} else if(m == F("LOCK")){
_method = HTTP_LOCK;
} else if(m == F("UNLOCK")){
_method = HTTP_UNLOCK;
} else if(m == F("PROPPATCH")){
_method = HTTP_PROPPATCH;
} else if(m == F("MKCOL")){
_method = HTTP_MKCOL;
} else if(m == F("MOVE")){
_method = HTTP_MOVE;
} else if(m == F("COPY")){
_method = HTTP_COPY;
} else if(m == F("RESERVED")){
_method = HTTP_RESERVED;
} else if(m == F("ANY")){
_method = HTTP_ANY;
}
String g;
@ -930,14 +922,6 @@ const __FlashStringHelper *AsyncWebServerRequest::methodToString() const {
else if(_method & HTTP_PATCH) return F("PATCH");
else if(_method & HTTP_HEAD) return F("HEAD");
else if(_method & HTTP_OPTIONS) return F("OPTIONS");
else if(_method & HTTP_PROPFIND) return F("PROPFIND");
else if(_method & HTTP_LOCK) return F("LOCK");
else if(_method & HTTP_UNLOCK) return F("UNLOCK");
else if(_method & HTTP_PROPPATCH) return F("PROPPATCH");
else if(_method & HTTP_MKCOL) return F("MKCOL");
else if(_method & HTTP_MOVE) return F("MOVE");
else if(_method & HTTP_COPY) return F("COPY");
else if(_method & HTTP_RESERVED) return F("RESERVED");
return F("UNKNOWN");
}

File diff suppressed because it is too large Load Diff

View File

@ -2,7 +2,7 @@
//File: edit.htm.gz, Size: 4503
#define edit_htm_gz_len 4503
const uint8_t edit_htm_gz[] PROGMEM = {
0x1F,0x8B,0x08,0x08,0x9B,0xC8,0x22,0x5F,0x02,0x00,0x65,0x64,0x69,0x74,0x2E,0x68,0x74,0x6D,0x00,0xB5,
0x1F,0x8B,0x08,0x08,0x5A,0xE6,0xAE,0x5F,0x02,0x00,0x65,0x64,0x69,0x74,0x2E,0x68,0x74,0x6D,0x00,0xB5,
0x1A,0x0B,0x5B,0xDB,0x36,0xF0,0xAF,0x18,0x6F,0x63,0xF6,0xE2,0x38,0x0E,0x50,0xD6,0x3A,0x18,0x16,0x1E,
0xEB,0xBB,0x50,0x12,0xDA,0xD1,0x8E,0xED,0x53,0x6C,0x25,0x56,0xB1,0x25,0xCF,0x96,0x09,0x34,0xCD,0x7F,
0xDF,0x49,0xF2,0x93,0x84,0xEE,0xF1,0x6D,0xA5,0x60,0x49,0xA7,0x3B,0xDD,0x9D,0xEE,0x25,0xD9,0x7B,0x1B,