work on GPIO handler

bigfix: memory leak in GetJPGStream
This commit is contained in:
Zwer2k
2021-06-18 01:29:59 +02:00
parent f24c40d780
commit d995c31b7b
15 changed files with 433 additions and 113 deletions

View File

@@ -1,3 +1,3 @@
copy "C:\Users\Muell\Documents\Programmieren\GitHub\AI-on-the-edge-device\code\.pio\build\esp32cam\firmware.bin" "C:\Users\Muell\Documents\Programmieren\GitHub\AI-on-the-edge-device\firmware\firmware.bin" copy "..\..\code\.pio\build\esp32cam\firmware.bin" "..\..\firmware\firmware.bin"
copy "C:\Users\Muell\Documents\Programmieren\GitHub\AI-on-the-edge-device\code\.pio\build\esp32cam\bootloader.bin" "C:\Users\Muell\Documents\Programmieren\GitHub\AI-on-the-edge-device\firmware\bootloader.bin" copy "..\..\code\.pio\build\esp32cam\bootloader.bin" "..\..\firmware\bootloader.bin"
copy "C:\Users\Muell\Documents\Programmieren\GitHub\AI-on-the-edge-device\code\.pio\build\esp32cam\partitions.bin" "C:\Users\Muell\Documents\Programmieren\GitHub\AI-on-the-edge-device\firmware\partitions.bin" copy "..\..\code\.pio\build\esp32cam\partitions.bin" "..\..\firmware\partitions.bin"

View File

@@ -1 +1 @@
powershell Compress-Archive "C:\Users\Muell\Documents\Programmieren\GitHub\AI-on-the-edge-device\sd-card\html\*.*" "C:\Users\Muell\Documents\Programmieren\GitHub\AI-on-the-edge-device\firmware\html.zip" powershell Compress-Archive "..\..\sd-card\html\*.*" "..\..\firmware\html.zip"

View File

@@ -1,4 +1,7 @@
#include <string.h> #include <string.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "Helper.h" #include "Helper.h"
#include "configFile.h" #include "configFile.h"

View File

@@ -13,7 +13,7 @@ public:
bool GetNextParagraph(std::string& aktparamgraph, bool &disabled, bool &eof); bool GetNextParagraph(std::string& aktparamgraph, bool &disabled, bool &eof);
bool getNextLine(std::string* rt, bool &disabled, bool &eof); bool getNextLine(std::string* rt, bool &disabled, bool &eof);
std::vector<std::string> ZerlegeZeile(std::string input, std::string delimiter = " =, \t"); std::vector<std::string> ZerlegeZeile(std::string input, std::string delimiter = " =, \t");
private: private:
FILE* pFile; FILE* pFile;
}; };

View File

@@ -22,68 +22,134 @@
// #define DEBUG_DETAIL_ON // #define DEBUG_DETAIL_ON
GpioPin::GpioPin(gpio_num_t gpio, const char* name, gpio_pin_mode_t mode, gpio_int_type_t interruptType) GpioPin::GpioPin(gpio_num_t gpio, const char* name, gpio_pin_mode_t mode, gpio_int_type_t interruptType, uint8_t dutyResolution, bool mqttEnable, bool httpEnable)
{ {
_gpio = gpio; _gpio = gpio;
_name = name; _name = name;
_mode = mode; _mode = mode;
_interruptType = interruptType; _interruptType = interruptType;
initGPIO(); //initGPIO();
} }
void GpioPin::initGPIO() GpioPin::~GpioPin()
{
printf("reset GPIO pin %d", _gpio);
gpio_reset_pin(_gpio);
}
void GpioPin::init()
{ {
gpio_config_t io_conf; gpio_config_t io_conf;
//disable interrupt //set interrupt
io_conf.intr_type = _interruptType; io_conf.intr_type = _interruptType;
//set as output mode //set as output mode
io_conf.mode = _mode == gpio_pin_mode_t::GPIO_PIN_MODE_OUTPUT ? gpio_mode_t::GPIO_MODE_OUTPUT : gpio_mode_t::GPIO_MODE_INPUT; io_conf.mode = _mode == gpio_pin_mode_t::GPIO_PIN_MODE_OUTPUT ? gpio_mode_t::GPIO_MODE_OUTPUT : gpio_mode_t::GPIO_MODE_INPUT;
//bit mask of the pins that you want to set,e.g.GPIO18/19 //bit mask of the pins that you want to set,e.g.GPIO18/19
io_conf.pin_bit_mask = (1ULL << _gpio); io_conf.pin_bit_mask = (1ULL << _gpio);
//disable pull-down mode //set pull-down mode
io_conf.pull_down_en = _mode == gpio_pin_mode_t::GPIO_PIN_MODE_INPUT_PULLDOWN ? gpio_pulldown_t::GPIO_PULLDOWN_ENABLE : gpio_pulldown_t::GPIO_PULLDOWN_DISABLE; io_conf.pull_down_en = _mode == gpio_pin_mode_t::GPIO_PIN_MODE_INPUT_PULLDOWN ? gpio_pulldown_t::GPIO_PULLDOWN_ENABLE : gpio_pulldown_t::GPIO_PULLDOWN_DISABLE;
//disable pull-up mode //set pull-up mode
io_conf.pull_up_en = _mode == gpio_pin_mode_t::GPIO_PIN_MODE_INPUT_PULLDOWN ? gpio_pullup_t::GPIO_PULLUP_ENABLE : gpio_pullup_t::GPIO_PULLUP_DISABLE; io_conf.pull_up_en = _mode == gpio_pin_mode_t::GPIO_PIN_MODE_INPUT_PULLDOWN ? gpio_pullup_t::GPIO_PULLUP_ENABLE : gpio_pullup_t::GPIO_PULLUP_DISABLE;
//configure GPIO with the given settings //configure GPIO with the given settings
gpio_config(&io_conf); gpio_config(&io_conf);
} }
void GpioPin::setValue(bool value) bool GpioPin::getValue(std::string* errorText)
{ {
if ((_mode != GPIO_PIN_MODE_INPUT) && (_mode != GPIO_PIN_MODE_INPUT_PULLUP) && (_mode != GPIO_PIN_MODE_INPUT_PULLDOWN)) {
(*errorText) = "GPIO is not in input mode";
}
return gpio_get_level(_gpio) == 1;
}
void GpioPin::setValue(bool value, std::string* errorText)
{
if ((_mode != GPIO_PIN_MODE_OUTPUT) && (_mode != GPIO_PIN_MODE_OUTPUT_PWM)) {
(*errorText) = "GPIO is not in output mode";
}
gpio_set_level(_gpio, value); gpio_set_level(_gpio, value);
} }
esp_err_t callHandleHttpRequest(httpd_req_t *req) esp_err_t callHandleHttpRequest(httpd_req_t *req)
{ {
return ((GpioHandler*)req->user_ctx)->handleHttpRequest(req); printf("callHandleHttpRequest\n");
GpioHandler *gpioHandler = (GpioHandler*)req->user_ctx;
return gpioHandler->handleHttpRequest(req);
} }
GpioHandler::GpioHandler(std::string configFile, httpd_handle_t server) void taskGpioHandler(void *pvParameter)
{ {
printf("taskGpioHandler\n");
((GpioHandler*)pvParameter)->init();
}
GpioHandler::GpioHandler(std::string configFile, httpd_handle_t httpServer)
{
printf("---- start GpioHandler ----\n");
_configFile = configFile; _configFile = configFile;
printf("-1-\n");
_httpServer = httpServer;
printf("-2-\n");
gpioMap = new std::map<gpio_num_t, GpioPin*>(); printf("register GPIO Uri\n");
registerGpioUri();
//xTaskCreate((TaskFunction_t)&taskGpioHandler, "taskGpioHandler", configMINIMAL_STACK_SIZE * 64, this, tskIDLE_PRIORITY+1, &xHandletaskGpioHandler);
}
GpioHandler::~GpioHandler() {
if (gpioMap != NULL) {
clear();
delete gpioMap;
}
}
void GpioHandler::init()
{
printf("freemem -3.1-: %u\n", esp_get_free_heap_size());
// TickType_t xDelay = 60000 / portTICK_PERIOD_MS;
// printf("wait before start %ldms\n", (long) xDelay);
// vTaskDelay( xDelay );
if (gpioMap == NULL) {
gpioMap = new std::map<gpio_num_t, GpioPin*>();
} else {
clear();
}
printf("read GPIO config and init GPIO\n");
printf("freemem -3.2-: %u\n", esp_get_free_heap_size());
readConfig(); readConfig();
registerGpioUri(server); printf("freemem -3.3-: %u\n", esp_get_free_heap_size());
for(std::map<gpio_num_t, GpioPin*>::iterator it = gpioMap->begin(); it != gpioMap->end(); ++it) {
it->second->init();
}
printf("freemem -3.4-: %u\n", esp_get_free_heap_size());
printf("GPIO init comleted\n");
} }
bool GpioHandler::readConfig() bool GpioHandler::readConfig()
{ {
ConfigFile configFile(_configFile); if (!gpioMap->empty())
std::vector<std::string> zerlegt; clear();
ConfigFile configFile = ConfigFile(_configFile);
std::vector<std::string> zerlegt;
std::string line = ""; std::string line = "";
bool disabledLine = false; bool disabledLine = false;
bool eof = false; bool eof = false;
while ((!configFile.GetNextParagraph(line, disabledLine, eof) || (line.compare("[GPIO]") != 0)) && !disabledLine && !eof) {}
while ((!configFile.GetNextParagraph(line, disabledLine, eof) || (line.compare("[GPIO]") != 0)) && !disabledLine && !eof) {}
if (eof) if (eof)
return false; return false;
while (configFile.getNextLine(&line, disabledLine, eof) && !configFile.isNewParagraph(line)) while (configFile.getNextLine(&line, disabledLine, eof) && !configFile.isNewParagraph(line))
{ {
zerlegt = configFile.ZerlegeZeile(line); zerlegt = configFile.ZerlegeZeile(line);
@@ -94,32 +160,45 @@ bool GpioHandler::readConfig()
// std::string gpioStr = pieces_match[1]; // std::string gpioStr = pieces_match[1];
if (zerlegt[0].rfind("IO", 0) == 0) if (zerlegt[0].rfind("IO", 0) == 0)
{ {
printf("Enable GP%s in %s mode\n", zerlegt[0].c_str(), zerlegt[1].c_str());
std::string gpioStr = zerlegt[0].substr(2, 2); std::string gpioStr = zerlegt[0].substr(2, 2);
gpio_num_t gpioNr = (gpio_num_t)atoi(gpioStr.c_str()); gpio_num_t gpioNr = (gpio_num_t)atoi(gpioStr.c_str());
gpio_pin_mode_t pinMode = resolvePinMode(zerlegt[1]); gpio_pin_mode_t pinMode = resolvePinMode(toLower(zerlegt[1]));
gpio_int_type_t intType = resolveIntType(zerlegt[2]); gpio_int_type_t intType = resolveIntType(toLower(zerlegt[2]));
(*gpioMap)[gpio_num_t::GPIO_NUM_16] = new GpioPin(gpioNr, zerlegt[3].c_str(), pinMode, intType); uint16_t dutyResolution = (uint8_t)atoi(zerlegt[3].c_str());
bool mqttEnabled = toLower(zerlegt[4]) == "true";
bool httpEnabled = toLower(zerlegt[5]) == "true";
(*gpioMap)[gpioNr] = new GpioPin(gpioNr, zerlegt[6].c_str(), pinMode, intType,dutyResolution, mqttEnabled, httpEnabled);
} }
} }
return true; return true;
} }
void GpioHandler::clear()
{
for(std::map<gpio_num_t, GpioPin*>::iterator it = gpioMap->begin(); it != gpioMap->end(); ++it) {
delete it->second;
}
gpioMap->clear();
}
void GpioHandler::registerGpioUri(httpd_handle_t server) { void GpioHandler::registerGpioUri()
{
ESP_LOGI(TAGPARTGPIO, "server_GPIO - Registering URI handlers"); ESP_LOGI(TAGPARTGPIO, "server_GPIO - Registering URI handlers");
httpd_uri_t camuri = { }; httpd_uri_t camuri = { };
camuri.method = HTTP_GET; camuri.method = HTTP_GET;
camuri.uri = "/GPIO"; camuri.uri = "/GPIO";
camuri.handler = callHandleHttpRequest; camuri.handler = callHandleHttpRequest;
camuri.user_ctx = (void*) this; camuri.user_ctx = (void*)this;
httpd_register_uri_handler(server, &camuri); httpd_register_uri_handler(_httpServer, &camuri);
} }
IRAM_ATTR esp_err_t GpioHandler::handleHttpRequest(httpd_req_t *req) esp_err_t GpioHandler::handleHttpRequest(httpd_req_t *req)
{ {
printf("handleHttpRequest\n");
#ifdef DEBUG_DETAIL_ON #ifdef DEBUG_DETAIL_ON
LogFile.WriteHeapInfo("handler_switch_GPIO - Start"); LogFile.WriteHeapInfo("handler_switch_GPIO - Start");
#endif #endif
@@ -128,50 +207,86 @@ IRAM_ATTR esp_err_t GpioHandler::handleHttpRequest(httpd_req_t *req)
char _query[200]; char _query[200];
char _valueGPIO[30]; char _valueGPIO[30];
char _valueStatus[30]; char _valueStatus[30];
std::string gpio, status, zw; std::string gpio, status;
printf("-1-\n");
if (httpd_req_get_url_query_str(req, _query, 200) == ESP_OK)
{ if (httpd_req_get_url_query_str(req, _query, 200) == ESP_OK) {
printf("Query: "); printf(_query); printf("\n"); printf("Query: "); printf(_query); printf("\n");
if (httpd_query_key_value(_query, "GPIO", _valueGPIO, 30) == ESP_OK) if (httpd_query_key_value(_query, "GPIO", _valueGPIO, 30) == ESP_OK)
{ {
printf("GPIO is found"); printf(_valueGPIO); printf("\n"); printf("GPIO is found "); printf(_valueGPIO); printf("\n");
gpio = std::string(_valueGPIO); gpio = std::string(_valueGPIO);
} else {
std::string resp_str = "GPIO No is not defined";
httpd_resp_send(req, resp_str.c_str(), resp_str.length());
return ESP_OK;
} }
if (httpd_query_key_value(_query, "Status", _valueStatus, 30) == ESP_OK) if (httpd_query_key_value(_query, "Status", _valueStatus, 30) == ESP_OK)
{ {
printf("Status is found"); printf(_valueStatus); printf("\n"); printf("Status is found "); printf(_valueStatus); printf("\n");
status = std::string(_valueStatus); status = std::string(_valueStatus);
} }
}; } else {
char* resp_str = "Error in call. Use /GPIO?GPIO=12&Status=high";
httpd_resp_send(req, resp_str, strlen(resp_str));
return ESP_OK;
}
printf("-2-\n");
status = toUpper(status); status = toUpper(status);
if (!(status == "HIGH") && !(status == "LOW")) if ((status != "HIGH") && (status != "LOW") && (status != "TRUE") && (status != "FALSE") && (status != "0") && (status != "1") && (status != ""))
{ {
zw = "Status not valid: " + status;; std::string zw = "Status not valid: " + status;
httpd_resp_sendstr_chunk(req, zw.c_str()); httpd_resp_sendstr_chunk(req, zw.c_str());
httpd_resp_sendstr_chunk(req, NULL); httpd_resp_sendstr_chunk(req, NULL);
return ESP_OK; return ESP_OK;
} }
printf("-3-\n");
int gpionum = stoi(gpio); int gpionum = stoi(gpio);
// frei: 16; 12-15; 2; 4 // nur 12 und 13 funktionieren 2: reboot, 4: BlitzLED, 14/15: DMA für SDKarte ??? // frei: 16; 12-15; 2; 4 // nur 12 und 13 funktionieren 2: reboot, 4: BlitzLED, 15: PSRAM, 14/15: DMA für SDKarte ???
gpio_num_t gpio_num = resolvePinNr(gpionum); gpio_num_t gpio_num = resolvePinNr(gpionum);
if (gpio_num == GPIO_NUM_NC) if (gpio_num == GPIO_NUM_NC)
{ {
zw = "GPIO" + std::to_string(gpionum) + " not support - only 12 & 13 free"; std::string zw = "GPIO" + std::to_string(gpionum) + " not support - only 12 & 13 free";
httpd_resp_sendstr_chunk(req, zw.c_str()); httpd_resp_sendstr_chunk(req, zw.c_str());
httpd_resp_sendstr_chunk(req, NULL); httpd_resp_sendstr_chunk(req, NULL);
return ESP_OK; return ESP_OK;
} }
(*gpioMap)[gpio_num]->setValue((status == "HIGH") || (status == "TRUE") || (status == "1")); if (gpioMap->count(gpio_num) == 0) {
char resp_str [30];
sprintf(resp_str, "GPIO%d is not registred", gpio_num);
httpd_resp_send(req, resp_str, strlen(resp_str));
return ESP_OK;
}
printf("-4-\n");
zw = "GPIO" + std::to_string(gpionum) + " switched to " + status; if (status == "")
httpd_resp_sendstr_chunk(req, zw.c_str()); {
httpd_resp_sendstr_chunk(req, NULL); std::string resp_str = "";
status = (*gpioMap)[gpio_num]->getValue(&resp_str) ? "HIGH" : "LOW";
if (resp_str == "") {
resp_str = status;
}
httpd_resp_sendstr_chunk(req, resp_str.c_str());
httpd_resp_sendstr_chunk(req, NULL);
}
else
{
std::string resp_str = "";
(*gpioMap)[gpio_num]->setValue((status == "HIGH") || (status == "TRUE") || (status == "1"), &resp_str);
if (resp_str == "") {
resp_str = "GPIO" + std::to_string(gpionum) + " switched to " + status;
}
httpd_resp_sendstr_chunk(req, resp_str.c_str());
httpd_resp_sendstr_chunk(req, NULL);
}
printf("-5-\n");
return ESP_OK; return ESP_OK;
}; };
@@ -180,14 +295,16 @@ gpio_num_t GpioHandler::resolvePinNr(uint8_t pinNr)
switch(pinNr) { switch(pinNr) {
case 0: case 0:
return GPIO_NUM_0; return GPIO_NUM_0;
case 1:
return GPIO_NUM_1;
case 3:
return GPIO_NUM_3;
case 4: case 4:
return GPIO_NUM_4; return GPIO_NUM_4;
case 12: case 12:
return GPIO_NUM_12; return GPIO_NUM_12;
case 13: case 13:
return GPIO_NUM_13; return GPIO_NUM_13;
case 16:
return GPIO_NUM_16;
default: default:
return GPIO_NUM_NC; return GPIO_NUM_NC;
} }
@@ -199,8 +316,10 @@ gpio_pin_mode_t GpioHandler::resolvePinMode(std::string input)
if( input == "input" ) return GPIO_PIN_MODE_INPUT; if( input == "input" ) return GPIO_PIN_MODE_INPUT;
if( input == "input-pullup" ) return GPIO_PIN_MODE_INPUT_PULLUP; if( input == "input-pullup" ) return GPIO_PIN_MODE_INPUT_PULLUP;
if( input == "input-pulldown" ) return GPIO_PIN_MODE_INPUT_PULLDOWN; if( input == "input-pulldown" ) return GPIO_PIN_MODE_INPUT_PULLDOWN;
if( input == "input-output" ) return GPIO_PIN_MODE_OUTPUT; if( input == "output" ) return GPIO_PIN_MODE_OUTPUT;
if( input == "input-output-pwm" ) return GPIO_PIN_MODE_OUTPUT_PWM; if( input == "output-pwm" ) return GPIO_PIN_MODE_OUTPUT_PWM;
if( input == "external-flash-pwm" ) return GPIO_PIN_MODE_EXTERNAL_FLASH_PWM;
if( input == "external-flash-ws281x" ) return GPIO_PIN_MODE_EXTERNAL_FLASH_WS281X;
return GPIO_PIN_MODE_DISABLED; return GPIO_PIN_MODE_DISABLED;
} }

View File

@@ -8,43 +8,55 @@
static const char *TAGPARTGPIO = "server_GPIO"; static const char *TAGPARTGPIO = "server_GPIO";
typedef enum { typedef enum {
GPIO_PIN_MODE_DISABLED = 0x0, GPIO_PIN_MODE_DISABLED = 0x0,
GPIO_PIN_MODE_INPUT = 0x1, GPIO_PIN_MODE_INPUT = 0x1,
GPIO_PIN_MODE_INPUT_PULLUP = 0x2, GPIO_PIN_MODE_INPUT_PULLUP = 0x2,
GPIO_PIN_MODE_INPUT_PULLDOWN = 0x3, GPIO_PIN_MODE_INPUT_PULLDOWN = 0x3,
GPIO_PIN_MODE_OUTPUT = 0x4, GPIO_PIN_MODE_OUTPUT = 0x4,
GPIO_PIN_MODE_OUTPUT_PWM = 0x5, GPIO_PIN_MODE_OUTPUT_PWM = 0x5,
GPIO_PIN_MODE_EXTERNAL_FLASH_PWM = 0x5,
GPIO_PIN_MODE_EXTERNAL_FLASH_WS281X = 0x5,
} gpio_pin_mode_t; } gpio_pin_mode_t;
class GpioPin { class GpioPin {
public: public:
GpioPin(gpio_num_t gpio, const char* name, gpio_pin_mode_t mode, gpio_int_type_t interruptType); GpioPin(gpio_num_t gpio, const char* name, gpio_pin_mode_t mode, gpio_int_type_t interruptType, uint8_t dutyResolution, bool mqttEnable, bool httpEnable);
void setValue(bool value); ~GpioPin();
bool getValue(std::string* errorText);
void setValue(bool value, std::string* errorText);
void init();
private: private:
gpio_num_t _gpio; gpio_num_t _gpio;
const char* _name; const char* _name;
gpio_pin_mode_t _mode; gpio_pin_mode_t _mode;
gpio_int_type_t _interruptType; gpio_int_type_t _interruptType;
void initGPIO();
}; };
esp_err_t callHandleHttpRequest(httpd_req_t *req); esp_err_t callHandleHttpRequest(httpd_req_t *req);
void taskGpioHandler(void *pvParameter);
class GpioHandler { class GpioHandler {
public: public:
GpioHandler(std::string configFile, httpd_handle_t server); GpioHandler(std::string configFile, httpd_handle_t httpServer);
~GpioHandler();
void registerGpioUri(httpd_handle_t server);
void init();
void clear();
void registerGpioUri();
esp_err_t handleHttpRequest(httpd_req_t *req); esp_err_t handleHttpRequest(httpd_req_t *req);
private: private:
std::string _configFile; std::string _configFile;
httpd_handle_t _httpServer;
std::map<gpio_num_t, GpioPin*> *gpioMap = NULL; std::map<gpio_num_t, GpioPin*> *gpioMap = NULL;
TaskHandle_t xHandletaskGpioHandler = NULL;
bool readConfig(); bool readConfig();
gpio_num_t resolvePinNr(uint8_t pinNr); gpio_num_t resolvePinNr(uint8_t pinNr);
gpio_pin_mode_t resolvePinMode(std::string input); gpio_pin_mode_t resolvePinMode(std::string input);
gpio_int_type_t resolveIntType(std::string input); gpio_int_type_t resolveIntType(std::string input);
}; };
void GpioHandlerStart();

View File

@@ -454,6 +454,12 @@ esp_err_t ClassFlowControll::GetJPGStream(std::string _fn, httpd_req_t *req)
esp_err_t result = ESP_FAIL; esp_err_t result = ESP_FAIL;
bool Dodelete = false; bool Dodelete = false;
if (flowalignment == NULL)
{
printf("Can't continue, flowalignment is NULL\n");
return ESP_FAIL;
}
if (_fn == "alg.jpg") if (_fn == "alg.jpg")
{ {
_send = flowalignment->ImageBasis; _send = flowalignment->ImageBasis;
@@ -485,7 +491,9 @@ esp_err_t ClassFlowControll::GetJPGStream(std::string _fn, httpd_req_t *req)
if (htmlinfo[i]->image_org) if (htmlinfo[i]->image_org)
_send = htmlinfo[i]->image_org; _send = htmlinfo[i]->image_org;
} }
delete htmlinfo[i];
} }
htmlinfo.clear();
htmlinfo = GetAllAnalog(); htmlinfo = GetAllAnalog();
for (int i = 0; i < htmlinfo.size(); ++i) for (int i = 0; i < htmlinfo.size(); ++i)
@@ -500,7 +508,9 @@ esp_err_t ClassFlowControll::GetJPGStream(std::string _fn, httpd_req_t *req)
if (htmlinfo[i]->image_org) if (htmlinfo[i]->image_org)
_send = htmlinfo[i]->image_org; _send = htmlinfo[i]->image_org;
} }
delete htmlinfo[i];
} }
htmlinfo.clear();
if (_send) if (_send)
{ {

View File

@@ -77,8 +77,9 @@ void memCopyGen(uint8_t* _source, uint8_t* _target, int _size)
FILE* OpenFileAndWait(const char* nm, char* _mode, int _waitsec) FILE* OpenFileAndWait(const char* nm, const char* _mode, int _waitsec)
{ {
printf("open config file %s in mode %s\n", nm, _mode);
FILE *pfile = fopen(nm, _mode); FILE *pfile = fopen(nm, _mode);
if (pfile == NULL) if (pfile == NULL)
@@ -313,6 +314,14 @@ string toUpper(string in)
return in; return in;
} }
string toLower(string in)
{
for (int i = 0; i < in.length(); ++i)
in[i] = tolower(in[i]);
return in;
}
// CPU Temp // CPU Temp
extern "C" uint8_t temprature_sens_read(); extern "C" uint8_t temprature_sens_read();
float temperatureRead() float temperatureRead()

View File

@@ -10,7 +10,7 @@ void FindReplace(std::string& line, std::string& oldString, std::string& newStri
void CopyFile(string input, string output); void CopyFile(string input, string output);
FILE* OpenFileAndWait(const char* nm, char* _mode, int _waitsec = 1); FILE* OpenFileAndWait(const char* nm, const char* _mode, int _waitsec = 1);
size_t findDelimiterPos(string input, string delimiter); size_t findDelimiterPos(string input, string delimiter);
//string trim(string istring); //string trim(string istring);
@@ -22,6 +22,7 @@ string getFileType(string filename);
int mkdir_r(const char *dir, const mode_t mode); int mkdir_r(const char *dir, const mode_t mode);
int removeFolder(const char* folderPath, const char* logTag); int removeFolder(const char* folderPath, const char* logTag);
string toLower(string in);
string toUpper(string in); string toUpper(string in);
float temperatureRead(); float temperatureRead();

View File

@@ -139,6 +139,19 @@ void task_NoSDBlink(void *pvParameter)
vTaskDelete(NULL); //Delete this task if it exits from the loop above vTaskDelete(NULL); //Delete this task if it exits from the loop above
} }
esp_err_t handler_gpio(httpd_req_t *req)
{
printf("freemem -3-: %u\n", esp_get_free_heap_size());
gpioHandler->init();
printf("freemem -4-: %u\n", esp_get_free_heap_size());
char resp_str [30];
sprintf(resp_str, "OK. freemem %u", esp_get_free_heap_size());
httpd_resp_send(req, resp_str, strlen(resp_str));
return ESP_OK;
}
extern "C" void app_main(void) extern "C" void app_main(void)
{ {
printf("Do Reset Camera\n"); printf("Do Reset Camera\n");
@@ -203,9 +216,19 @@ extern "C" void app_main(void)
register_server_file_uri(server, "/sdcard"); register_server_file_uri(server, "/sdcard");
register_server_ota_sdcard_uri(server); register_server_ota_sdcard_uri(server);
httpd_uri_t camuri = { };
camuri.method = HTTP_GET;
camuri.uri = "/test";
camuri.handler = handler_gpio;
camuri.user_ctx = (void*)server;
httpd_register_uri_handler(server, &camuri);
#ifdef __SD_USE_ONE_LINE_MODE__ #ifdef __SD_USE_ONE_LINE_MODE__
printf("freemem -1-: %u\n", esp_get_free_heap_size());
gpioHandler = new GpioHandler(CONFIG_FILE, server); gpioHandler = new GpioHandler(CONFIG_FILE, server);
printf("freemem -2-: %u\n", esp_get_free_heap_size());
#endif #endif
printf("vor reg server main\n"); printf("vor reg server main\n");
register_server_main_uri(server, "/sdcard"); register_server_main_uri(server, "/sdcard");
@@ -213,3 +236,4 @@ extern "C" void app_main(void)
printf("vor dotautostart\n"); printf("vor dotautostart\n");
TFliteDoAutoStart(); TFliteDoAutoStart();
} }

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@@ -139,8 +139,8 @@ textarea {
</td> </td>
<td> <td>
<select id="MakeImage_ImageSize_value1"> <select id="MakeImage_ImageSize_value1">
<option value="0" selected>VGA</option> <option value="VGA" selected>VGA</option>
<option value="1" >QVGA</option> <option value="QVGA" >QVGA</option>
</select> </select>
</td> </td>
<td class="description"> <td class="description">
@@ -168,8 +168,8 @@ textarea {
</td> </td>
<td> <td>
<select id="MakeImage_FixedExposure_value1"> <select id="MakeImage_FixedExposure_value1">
<option value="0" selected>true</option> <option value="true" selected>true</option>
<option value="1" >false</option> <option value="false" >false</option>
</select> </select>
</td> </td>
<td style="font-size: 80%;"> <td style="font-size: 80%;">
@@ -247,9 +247,9 @@ textarea {
</td> </td>
<td> <td>
<select id="Alignment_AlignmentAlgo_value1"> <select id="Alignment_AlignmentAlgo_value1">
<option value="0" selected>Default</option> <option value="default" selected>Default</option>
<option value="1" >HighAccurity</option> <option value="highAccurity" >HighAccurity</option>
<option value="2" >Fast</option> <option value="fast" >Fast</option>
</select> </select>
</td> </td>
<td style="font-size: 80%;"> <td style="font-size: 80%;">
@@ -354,8 +354,8 @@ textarea {
</td> </td>
<td> <td>
<select id="Analog_ExtendedResolution_value1"> <select id="Analog_ExtendedResolution_value1">
<option value="0" selected>true</option> <option value="true" selected>true</option>
<option value="1" >false</option> <option value="false" >false</option>
</select> </select>
</td> </td>
<td style="font-size: 80%;"> <td style="font-size: 80%;">
@@ -402,8 +402,8 @@ textarea {
</td> </td>
<td> <td>
<select id="PostProcessing_PreValueUse_value1"> <select id="PostProcessing_PreValueUse_value1">
<option value="0" selected>true</option> <option value="true" selected>true</option>
<option value="1" >false</option> <option value="false" >false</option>
</select> </select>
</td> </td>
<td style="font-size: 80%;"> <td style="font-size: 80%;">
@@ -433,8 +433,8 @@ textarea {
</td> </td>
<td> <td>
<select id="PostProcessing_AllowNegativeRates_value1"> <select id="PostProcessing_AllowNegativeRates_value1">
<option value="0" selected>true</option> <option value="true" selected>true</option>
<option value="1" >false</option> <option value="false" >false</option>
</select> </select>
</td> </td>
<td style="font-size: 80%;"> <td style="font-size: 80%;">
@@ -464,8 +464,8 @@ textarea {
</td> </td>
<td> <td>
<select id="PostProcessing_ErrorMessage_value1"> <select id="PostProcessing_ErrorMessage_value1">
<option value="0" selected>true</option> <option value="true" selected>true</option>
<option value="1" >false</option> <option value="false" >false</option>
</select> </select>
</td> </td>
<td style="font-size: 80%;"> <td style="font-size: 80%;">
@@ -481,8 +481,8 @@ textarea {
</td> </td>
<td> <td>
<select id="PostProcessing_CheckDigitIncreaseConsistency_value1"> <select id="PostProcessing_CheckDigitIncreaseConsistency_value1">
<option value="0" selected>true</option> <option value="true" selected>true</option>
<option value="1" >false</option> <option value="false" >false</option>
</select> </select>
</td> </td>
<td style="font-size: 80%;"> <td style="font-size: 80%;">
@@ -645,8 +645,8 @@ textarea {
</td> </td>
<td> <td>
<select id="AutoTimer_AutoStart_value1"> <select id="AutoTimer_AutoStart_value1">
<option value="0" selected>true</option> <option value="true" selected>true</option>
<option value="1" >false</option> <option value="false" >false</option>
</select> </select>
</td> </td>
<td style="font-size: 80%;"> <td style="font-size: 80%;">
@@ -670,47 +670,186 @@ textarea {
<tr> <tr>
<td colspan="4" style="padding-left: 20px;"><h4><input type="checkbox" id="Category_GPIO_enabled" value="1" onclick='UpdateAfterCategoryCheck()' unchecked > GPIO Settings</h4></td> <td colspan="4" style="padding-left: 20px;"><h4><input type="checkbox" id="Category_GPIO_enabled" value="1" onclick='UpdateAfterCategoryCheck()' unchecked > GPIO Settings</h4></td>
</tr> </tr>
<tr class="GPIO_IO16">
<tr class="GPIO_IO12">
<td width="20px" style="padding-left: 40px;"> <td width="20px" style="padding-left: 40px;">
<input type="checkbox" id="GPIO_IO16_enabled" value="1" onclick = 'InvertEnableItem("GPIO", "IO16")' unchecked> <input type="checkbox" id="GPIO_IO12_enabled" value="1" onclick = 'InvertEnableItem("GPIO", "IO12")' unchecked>
</td> </td>
<td> <td>
<span id="GPIO_IO16_text">GPIO 16 state</span> <span id="GPIO_IO12_text">GPIO 12 state</span>
</td> </td>
<td> <td>
<td"> <td">
<select id="GPIO_IO16_value1"> <select id="GPIO_IO12_value1">
<option value="input" >input</option> <option value="input">input</option>
<option value="output" >output</option> <option value="input-pullup">input pullup</option>
<option value="input-pulldown">input pulldown</option>
<option value="output">output</option>
<option value="output-pwm" disabled>output pwm (not implemented)</option>
<option value="external-flash-pwm" disabled>external flash light pwm controlled (not implemented)</option>
<option value="external-flash-ws281x" disabled>external flash light ws281x controlled (not implemented)</option>
</select> </select>
</td> </td>
</td> </td>
<td class="description"> <td class="description">
GPIO 16 is usable without restrictions GPIO 12 is usable without restrictions
</td> </td>
</tr> </tr>
<tr class="GPIO_IO16"> <tr class="GPIO_IO12">
<td width="20px" style="padding-left: 40px;"></td> <td width="20px" style="padding-left: 40px;"></td>
<td> <td>
<span>GPIO 16 use interrupt</span> <span>GPIO 12 use interrupt</span>
</td> </td>
<td> <td>
<td"><input type="checkbox" id="GPIO_IO16_value2"></td> <td">
<select id="GPIO_IO12_value2">
<option value="disabled">disabled</option>
<option value="rising-edge" disabled>rising edge (not implemented)</option>
<option value="falling-edge" disabled>falling edge (not implemented)</option>
</select>
</td>
</td> </td>
<td class="description"> <td class="description">
GPIO 16 enable interrupt trigger GPIO 12 enable interrupt trigger
</td> </td>
</tr> </tr>
<tr class="GPIO_IO16"> <tr class="GPIO_IO12">
<td width="20px" style="padding-left: 40px;"></td> <td width="20px" style="padding-left: 40px;"></td>
<td> <td>
<span>GPIO 16 name</span> <span>GPIO 12 PWM duty resolution</span>
</td> </td>
<td> <td>
<td"><input type="text" id="GPIO_IO16_value3"></td> <td"><input type="number" id="GPIO_IO12_value3" min="1" max="20"></td>
</td> </td>
<td class="description"> <td class="description">
GPIO 16 MQTT topic name (empty = gpio16). Allowed characters (a-z, A-Z, 0-9, _, -) GPIO 12 LEDC PWM duty resolution in bit
</td>
</tr>
<tr class="GPIO_IO12">
<td width="20px" style="padding-left: 40px;"></td>
<td>
<span>GPIO 12 enable MQTT</span>
</td>
<td>
<td"><input type="checkbox" id="GPIO_IO12_value4"></td>
</td>
<td class="description">
GPIO 12 enable MQTT publishing/subscribing
</td>
</tr>
<tr class="GPIO_IO12">
<td width="20px" style="padding-left: 40px;"></td>
<td>
<span>GPIO 12 enable HTTP</span>
</td>
<td>
<td"><input type="checkbox" id="GPIO_IO12_value5"></td>
</td>
<td class="description">
GPIO 12 enable HTTP write/read
</td>
</tr>
<tr class="GPIO_IO12">
<td width="20px" style="padding-left: 40px;"></td>
<td>
<span>GPIO 12 name</span>
</td>
<td>
<td"><input type="text" id="GPIO_IO12_value6"></td>
</td>
<td class="description">
GPIO 12 MQTT topic name (empty = gpio12). Allowed characters (a-z, A-Z, 0-9, _, -)
</td>
</tr>
<tr class="GPIO_IO13">
<td width="20px" style="padding-left: 40px;">
<input type="checkbox" id="GPIO_IO13_enabled" value="1" onclick = 'InvertEnableItem("GPIO", "IO13")' unchecked>
</td>
<td>
<span id="GPIO_IO13_text">GPIO 13 state</span>
</td>
<td>
<td">
<select id="GPIO_IO13_value1">
<option value="input">input</option>
<option value="input-pullup">input pullup</option>
<option value="input-pulldown">input pulldown</option>
<option value="output">output</option>
<option value="output-pwm" disabled>output pwm (not implemented)</option>
<option value="external-flash-pwm" disabled>external flash light pwm controlled (not implemented)</option>
<option value="external-flash-ws281x" disabled>external flash light ws281x controlled (not implemented)</option>
</select>
</td>
</td>
<td class="description">
GPIO 13 is usable without restrictions
</td>
</tr>
<tr class="GPIO_IO13">
<td width="20px" style="padding-left: 40px;"></td>
<td>
<span>GPIO 13 use interrupt</span>
</td>
<td>
<td">
<select id="GPIO_IO13_value2">
<option value="disabled">disabled</option>
<option value="rising-edge" disabled>rising edge (not implemented)</option>
<option value="falling-edge" disabled>falling edge (not implemented)</option>
</select>
</td>
</td>
<td class="description">
GPIO 13 enable interrupt trigger
</td>
</tr>
<tr class="GPIO_IO13">
<td width="20px" style="padding-left: 40px;"></td>
<td>
<span>GPIO 13 PWM duty resolution</span>
</td>
<td>
<td"><input type="number" id="GPIO_IO13_value3" min="1" max="20"></td>
</td>
<td class="description">
GPIO 13 LEDC PWM duty resolution in bit
</td>
</tr>
<tr class="GPIO_IO13">
<td width="20px" style="padding-left: 40px;"></td>
<td>
<span>GPIO 13 enable MQTT</span>
</td>
<td>
<td"><input type="checkbox" id="GPIO_IO13_value4"></td>
</td>
<td class="description">
GPIO 13 enable MQTT publishing/subscribing
</td>
</tr>
<tr class="GPIO_IO13">
<td width="20px" style="padding-left: 40px;"></td>
<td>
<span>GPIO 13 enable HTTP</span>
</td>
<td>
<td"><input type="checkbox" id="GPIO_IO13_value5"></td>
</td>
<td class="description">
GPIO 13 enable HTTP write/read
</td>
</tr>
<tr class="GPIO_IO13">
<td width="20px" style="padding-left: 40px;"></td>
<td>
<span>GPIO 13 name</span>
</td>
<td>
<td"><input type="text" id="GPIO_IO13_value6"></td>
</td>
<td class="description">
GPIO 13 MQTT topic name (empty = gpio13). Allowed characters (a-z, A-Z, 0-9, _, -)
</td> </td>
</tr> </tr>
@@ -726,8 +865,8 @@ textarea {
</td> </td>
<td> <td>
<select id="Debug_Logfile_value1"> <select id="Debug_Logfile_value1">
<option value="0" selected>true</option> <option value="true" selected>true</option>
<option value="1" >false</option> <option value="false" >false</option>
</select> </select>
</td> </td>
<td class="description"> <td class="description">
@@ -873,9 +1012,9 @@ function WriteParameter(_param, _category, _cat, _name, _optional){
for (var j = 1; j <= anzpara; ++j) { for (var j = 1; j <= anzpara; ++j) {
let element = document.getElementById(_cat+"_"+_name+"_value"+j); let element = document.getElementById(_cat+"_"+_name+"_value"+j);
if (element.tagName.toLowerCase() == "select") { if (element.tagName.toLowerCase() == "select") {
var textToFind = _param[_cat][_name]["value1"]; var textToFind = _param[_cat][_name]["value"+j];
for (var i = 0; i < element.options.length; i++) { for (var i = 0; i < element.options.length; i++) {
if (element.options[i].text.toLowerCase() === textToFind.toLowerCase()) { if (element.options[i].value.toLowerCase() === textToFind.toLowerCase()) {
element.selectedIndex = i; element.selectedIndex = i;
break; break;
} }
@@ -998,23 +1137,23 @@ function ReadParameter(_param, _cat, _name, _optional){
_param[_cat][_name]["enabled"] = document.getElementById(_cat+"_"+_name+"_enabled").checked; _param[_cat][_name]["enabled"] = document.getElementById(_cat+"_"+_name+"_enabled").checked;
} }
for (var j = 0; j < _param[_cat][_name]["anzParam"]; ++j) { for (var j = 1; j <= _param[_cat][_name]["anzParam"]; ++j) {
let element = document.getElementById(_cat+"_"+_name+"_value"+(j+1)); let element = document.getElementById(_cat+"_"+_name+"_value"+j);
if (element.tagName.toLowerCase() == "select") { if (element.tagName.toLowerCase() == "select") {
_param[_cat][_name]["value1"] = element.selectedIndex > -1 ? element.options[element.selectedIndex].text : ""; _param[_cat][_name]["value"+j] = element.selectedIndex > -1 ? element.options[element.selectedIndex].value : "";
} }
else if ((element.getAttribute("type") != null) && (element.getAttribute("type").toLowerCase() == "checkbox")) { else if ((element.getAttribute("type") != null) && (element.getAttribute("type").toLowerCase() == "checkbox")) {
_param[_cat][_name]["value"+(j+1)] = element.checked; _param[_cat][_name]["value"+j] = element.checked;
} }
else { else {
if ((_param[_cat][_name].checkRegExList != null) && (_param[_cat][_name].checkRegExList[j] != null)) { if ((_param[_cat][_name].checkRegExList != null) && (_param[_cat][_name].checkRegExList[j-1] != null)) {
if (!element.value.match(_param[_cat][_name].checkRegExList[j])) { if (!element.value.match(_param[_cat][_name].checkRegExList[j-1])) {
element.classList.add("invalid-input"); element.classList.add("invalid-input");
} else { } else {
element.classList.remove("invalid-input"); element.classList.remove("invalid-input");
} }
} }
_param[_cat][_name]["value"+(j+1)] = element.value; _param[_cat][_name]["value"+j] = element.value;
} }
} }
} }
@@ -1070,7 +1209,8 @@ function UpdateInput() {
WriteParameter(param, category, "MQTT", "user", true); WriteParameter(param, category, "MQTT", "user", true);
WriteParameter(param, category, "MQTT", "password", true); WriteParameter(param, category, "MQTT", "password", true);
WriteParameter(param, category, "GPIO", "IO16", true); WriteParameter(param, category, "GPIO", "IO12", true);
WriteParameter(param, category, "GPIO", "IO13", true);
WriteParameter(param, category, "AutoTimer", "AutoStart", false); WriteParameter(param, category, "AutoTimer", "AutoStart", false);
WriteParameter(param, category, "AutoTimer", "Intervall", false); WriteParameter(param, category, "AutoTimer", "Intervall", false);
@@ -1134,7 +1274,8 @@ function ReadParameterAll()
ReadParameter(param, "MQTT", "user", true); ReadParameter(param, "MQTT", "user", true);
ReadParameter(param, "MQTT", "password", true); ReadParameter(param, "MQTT", "password", true);
ReadParameter(param, "GPIO", "IO16", true); ReadParameter(param, "GPIO", "IO12", true);
ReadParameter(param, "GPIO", "IO13", true);
ReadParameter(param, "AutoTimer", "AutoStart", false); ReadParameter(param, "AutoTimer", "AutoStart", false);
ReadParameter(param, "AutoTimer", "Intervall", false); ReadParameter(param, "AutoTimer", "Intervall", false);

View File

@@ -97,7 +97,8 @@ function ParseConfig() {
category[catname]["enabled"] = false; category[catname]["enabled"] = false;
category[catname]["found"] = false; category[catname]["found"] = false;
param[catname] = new Object(); param[catname] = new Object();
ParamAddValue(param, catname, "IO16", 3, [null, null, /^[a-zA-Z0-9_-]*$/]); ParamAddValue(param, catname, "IO12", 6, [null, null, /^[0-9]*$/, null, null, /^[a-zA-Z0-9_-]*$/]);
ParamAddValue(param, catname, "IO13", 6, [null, null, /^[0-9]*$/, null, null, /^[a-zA-Z0-9_-]*$/]);
var catname = "AutoTimer"; var catname = "AutoTimer";
category[catname] = new Object(); category[catname] = new Object();