Compare commits

..

No commits in common. "master" and "v1.0.2-rc1" have entirely different histories.

300 changed files with 1807 additions and 379980 deletions

70
.gitignore vendored
View File

@ -1,70 +0,0 @@
# Created by https://www.toptal.com/developers/gitignore/api/c++,macos
# Edit at https://www.toptal.com/developers/gitignore?templates=c++,macos
### C++ ###
# Prerequisites
*.d
# Compiled Object files
*.slo
*.lo
*.o
*.obj
# Precompiled Headers
*.gch
*.pch
# Compiled Dynamic libraries
*.so
*.dylib
*.dll
# Fortran module files
*.mod
*.smod
# Compiled Static libraries
*.lai
*.la
*.a
*.lib
# Executables
*.out
*.app
### macOS ###
# General
.DS_Store
.AppleDouble
.LSOverride
# Icon must end with two \r
Icon
# Thumbnails
._*
# Files that might appear in the root of a volume
.DocumentRevisions-V100
.fseventsd
.Spotlight-V100
.TemporaryItems
.Trashes
.VolumeIcon.icns
.com.apple.timemachine.donotpresent
# Directories potentially created on remote AFP share
.AppleDB
.AppleDesktop
Network Trash Folder
Temporary Items
.apdisk
### macOS Patch ###
# iCloud generated files
*.icloud
# End of https://www.toptal.com/developers/gitignore/api/c++,macos

View File

@ -0,0 +1,37 @@
/**
@file Camera_cfg.h
@brief Here is saved camera GPIO cfg for camera module OV2640
@author Miroslav Pivovarsky
Contact: miroslav.pivovarsky@gmail.com
@bug: no know bug
*/
#ifndef _CAMERA_CFG_H_
#define _CAMERA_CFG_H_
// OV2640 camera module pins (CAMERA_MODEL_AI_THINKER)
#define PWDN_GPIO_NUM 32 ///< Power down control pin
#define RESET_GPIO_NUM -1 ///< Reset control pin
#define XCLK_GPIO_NUM 0 ///< External clock pin
#define SIOD_GPIO_NUM 26 ///< SCCB: SI/O data pin
#define SIOC_GPIO_NUM 27 ///< SCCB: SI/O control pin
#define Y9_GPIO_NUM 35 ///< SCCB: Y9 pin
#define Y8_GPIO_NUM 34 ///< SCCB: Y8 pin
#define Y7_GPIO_NUM 39 ///< SCCB: Y7 pin
#define Y6_GPIO_NUM 36 ///< SCCB: Y6 pin
#define Y5_GPIO_NUM 21 ///< SCCB: Y5 pin
#define Y4_GPIO_NUM 19 ///< SCCB: Y4 pin
#define Y3_GPIO_NUM 18 ///< SCCB: Y3 pin
#define Y2_GPIO_NUM 5 ///< SCCB: Y2 pin
#define VSYNC_GPIO_NUM 25 ///< Vertical sync pin
#define HREF_GPIO_NUM 23 ///< Line sync pin
#define PCLK_GPIO_NUM 22 ///< Pixel clock pin
#define FLASH_GPIO_NUM 4 ///< Flash control pin
#endif
/* EOF */

View File

@ -9,7 +9,8 @@
@bug: no know bug
*/
#pragma once
#ifndef _CERTIFICATE_H_
#define _CERTIFICATE_H_
/*
echo -n | openssl s_client -servername connect.prusa.com -connect connect.prusa.com:443 | sed -ne '/-BEGIN CERTIFICATE-/,/-END CERTIFICATE-/p' > connect_prusa_com.crt
@ -53,4 +54,6 @@ emyPxgcYxn/eR44/KJ4EBs+lVDR3veyJm+kXQ99b21/+jh5Xos1AnX5iItreGCc=
-----END CERTIFICATE-----
)rawliteral";
#endif
/* EOF */

View File

@ -9,7 +9,8 @@
@bug: no know bug
*/
#pragma once
#ifndef _CERTIFICATE_OTA_H_
#define _CERTIFICATE_OTA_H_
/*
echo -n | openssl s_client -servername github.com -connect github.com:443 | sed -ne '/-BEGIN CERTIFICATE-/,/-END CERTIFICATE-/p' > github_com.crt
@ -134,4 +135,6 @@ RNZu9YO6bVi9JNlWSOrvxKJGgYhqOkbRqZtNyWHa0V1Xahg=
-----END CERTIFICATE-----
)rawliteral";
#endif
/* EOF */

View File

@ -4,18 +4,21 @@
It's neccesary install support for ESP32 board to the arduino IDE. In the board manager we need add next link
https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json
Then we can install "ESP32 by Espressif Systems" board in the board manager.
ESP32 lib version: 3.0.2 (ESP-IDF v5.1.4) by Espressif Systems
ESP32 lib version: 2.0.16 (ESP-IDF v4.4.7) by Espressif Systems
This project uses other libraries. It is necessary to install them in the arduino IDE.
- Library - License - Version - Link
- ESPAsyncWebServer - LGPL 3.0 - 3.4.5 - https://github.com/mathieucarbou/ESPAsyncWebServer
- AsyncTCP - LGPL 3.0 - 3.3.1 - https://github.com/mathieucarbou/AsyncTCP
- ArduinoJson - MIT - 7.3.0 - https://github.com/bblanchon/ArduinoJson
- ArduinoUniqueID - MIT - 1.3.0 - https://github.com/ricaun/ArduinoUniqueID
- arduino-esp32 - LGPL 2.1 - 3.1.0 - https://github.com/espressif/arduino-esp32
- DHTnew - MIT - 0.5.2 - https://github.com/RobTillaart/DHTNew
- Library - License - Version - Link
- ESPAsyncWebSrv - LGPL 2.1 - 1.2.7 - https://github.com/dvarrel/ESPAsyncWebSrv
- AsyncTCP - LGPL 3.0 - 1.1.4 - https://github.com/dvarrel/ESPAsyncTCP
- ArduinoJson - MIT - 7.0.4 - https://github.com/bblanchon/ArduinoJson
- ArduinoUniqueID - MIT - 1.3.0 - https://github.com/ricaun/ArduinoUniqueID
- ESP32 - LGPL 2.1 - 2.0.16 - https://github.com/espressif/arduino-esp32
Arduino IDE configuration for the MCU are stored in the module_XXX.h file.
Board configuration in the arduino IDE 2.3.2
Tools -> Board -> ESP32 Arduino -> AI Thinker ESP32
Tools -> Flash frequency -> 80MHz
Tools -> Flash Mode -> DIO
Tools -> Partition scheme -> Minimal SPIFFS (1.9MB APP with OTA/190KB SPIFFS)
When flashing the firmware to a new, empty ESP32-CAM device for the first time, it is necessary to use the 'Erase' function.
This can be found under 'Tools' -> 'Erase all Flash Before Sketch Upload' -> 'Enable'.
@ -23,6 +26,15 @@
If you do not disable this option, your camera configuration will continue to be erased from the flash memory
after uploading new firmware from the Arduino IDE.
Here is partitions table
# Name, Type, SubType, Offset, Size, Flags
nvs, data, nvs, 0x9000, 0x5000,
otadata, data, ota, 0xe000, 0x2000,
app0, app, ota_0, 0x10000, 0x1E0000,
app1, app, ota_1, 0x1F0000,0x1E0000,
spiffs, data, spiffs, 0x3D0000,0x20000,
coredump, data, coredump,0x3F0000,0x10000,
Project: ESP32 PrusaConnect Camera
Developed for: Prusa Research, prusa3d.com
Author: Miroslav Pivovarsky
@ -30,12 +42,14 @@
*/
/* includes */
#include <WiFi.h>
#include "Arduino.h"
#include <esp_task_wdt.h>
#include <ESPmDNS.h>
#include <esp_wifi.h>
#include "esp32-hal-cpu.h"
#include "WebServer.h"
#include "server.h"
#include "cfg.h"
#include "var.h"
#include "mcu_cfg.h"
@ -44,6 +58,7 @@
#include "log.h"
#include "connect.h"
#include "wifi_mngt.h"
#include "stream.h"
#include "serial_cfg.h"
void setup() {
@ -88,7 +103,6 @@ void setup() {
/* init camera interface */
SystemCamera.Init();
SystemCamera.CapturePhoto();
SystemCamera.CaptureReturnFrameBuffer();
/* init WEB server */
Server_InitWebServer();
@ -96,43 +110,30 @@ void setup() {
/* init class for communication with PrusaConnect */
Connect.Init();
/* init external temperature sensor */
ExternalTemperatureSensor.Init();
/* init tasks */
SystemLog.AddEvent(LogLevel_Info, F("Start tasks"));
xTaskCreatePinnedToCore(System_TaskMain, "SystemNtpOtaUpdate", 8000, NULL, 1, &Task_SystemMain, 0); /*function, description, stack size, parameters, priority, task handle, core*/
xTaskCreatePinnedToCore(System_TaskCaptureAndSendPhoto, "CaptureAndSendPhoto", 6000, NULL, 2, &Task_CapturePhotoAndSend, 0); /*function, description, stack size, parameters, priority, task handle, core*/
xTaskCreatePinnedToCore(System_TaskWifiManagement, "WiFiManagement", 3800, NULL, 3, &Task_WiFiManagement, 0); /*function, description, stack size, parameters, priority, task handle, core*/
xTaskCreatePinnedToCore(System_TaskSdCardCheck, "CheckMicroSdCard", 3300, NULL, 4, &Task_SdCardCheck, 0); /*function, description, stack size, parameters, priority, task handle, core*/
xTaskCreatePinnedToCore(System_TaskSerialCfg, "CheckSerialConfiguration", 3300, NULL, 5, &Task_SerialCfg, 0); /*function, description, stack size, parameters, priority, task handle, core*/
xTaskCreatePinnedToCore(System_TaskStreamTelemetry, "PrintStreamTelemetry", 3300, NULL, 6, &Task_StreamTelemetry, 0); /*function, description, stack size, parameters, priority, task handle, core*/
xTaskCreatePinnedToCore(System_TaskSysLed, "SystemLed", 3000, NULL, 7, &Task_SysLed, 0); /*function, description, stack size, parameters, priority, task handle, core*/
xTaskCreatePinnedToCore(System_TaskWiFiWatchdog, "WiFiWatchdog", 3500, NULL, 8, &Task_WiFiWatchdog, 0); /*function, description, stack size, parameters, priority, task handle, core*/
/* init wdg */
SystemLog.AddEvent(LogLevel_Info, F("Init WDG"));
esp_task_wdt_config_t twdt_config;
twdt_config.timeout_ms = WDG_TIMEOUT;
twdt_config.idle_core_mask = (1 << portNUM_PROCESSORS) - 1, /* Bitmask of all cores */
twdt_config.trigger_panic = true;
esp_task_wdt_init(&twdt_config); /* enable panic so ESP32 restarts */
esp_task_wdt_reconfigure(&twdt_config);
ESP_ERROR_CHECK(esp_task_wdt_add(NULL)); /* add current thread to WDT watch */
esp_task_wdt_reset(); /* reset wdg */
/* init tasks */
SystemLog.AddEvent(LogLevel_Info, F("Start tasks"));
xTaskCreatePinnedToCore(System_TaskMain, "SystemNtpOtaUpdate", 5200, NULL, 1, &Task_SystemMain, 0); /*function, description, stack size, parameters, priority, task handle, core*/
ESP_ERROR_CHECK(esp_task_wdt_add(Task_SystemMain));
xTaskCreatePinnedToCore(System_TaskCaptureAndSendPhoto, "CaptureAndSendPhoto", 4400, NULL, 2, &Task_CapturePhotoAndSend, 0); /*function, description, stack size, parameters, priority, task handle, core*/
ESP_ERROR_CHECK(esp_task_wdt_add(Task_CapturePhotoAndSend));
xTaskCreatePinnedToCore(System_TaskWifiManagement, "WiFiManagement", 2700, NULL, 3, &Task_WiFiManagement, 0); /*function, description, stack size, parameters, priority, task handle, core*/
ESP_ERROR_CHECK(esp_task_wdt_add(Task_WiFiManagement));
#if (true == ENABLE_SD_CARD)
xTaskCreatePinnedToCore(System_TaskSdCardCheck, "CheckMicroSdCard", 3000, NULL, 4, &Task_SdCardCheck, 0); /*function, description, stack size, parameters, priority, task handle, core*/
ESP_ERROR_CHECK(esp_task_wdt_add(Task_SdCardCheck));
#endif
xTaskCreatePinnedToCore(System_TaskSerialCfg, "CheckSerialConfiguration", 2300, NULL, 5, &Task_SerialCfg, 0); /*function, description, stack size, parameters, priority, task handle, core*/
ESP_ERROR_CHECK(esp_task_wdt_add(Task_SerialCfg));
xTaskCreatePinnedToCore(System_TaskSystemTelemetry, "PrintSystemTelemetry", 2200, NULL, 6, &Task_SystemTelemetry, 0); /*function, description, stack size, parameters, priority, task handle, core*/
ESP_ERROR_CHECK(esp_task_wdt_add(Task_SystemTelemetry));
xTaskCreatePinnedToCore(System_TaskSysLed, "SystemLed", 2000, NULL, 7, &Task_SysLed, 0); /*function, description, stack size, parameters, priority, task handle, core*/
ESP_ERROR_CHECK(esp_task_wdt_add(Task_SysLed));
xTaskCreatePinnedToCore(System_TaskWiFiWatchdog, "WiFiWatchdog", 2200, NULL, 8, &Task_WiFiWatchdog, 0); /*function, description, stack size, parameters, priority, task handle, core*/
ESP_ERROR_CHECK(esp_task_wdt_add(Task_WiFiWatchdog));
//xTaskCreatePinnedToCore(System_TaskSdCardRemove, "SdCardRemove", 3000, NULL, 9, &Task_SdCardFileRemove, 0); /*function, description, stack size, parameters, priority, task handle, core*/
//esp_task_wdt_add(Task_SdCardFileRemove);
esp_task_wdt_init(WDG_TIMEOUT, true); /* enable panic so ESP32 restarts */
esp_task_wdt_add(NULL); /* add current thread to WDT watch */
esp_task_wdt_add(Task_CapturePhotoAndSend);
esp_task_wdt_add(Task_WiFiManagement);
esp_task_wdt_add(Task_SystemMain);
esp_task_wdt_add(Task_SdCardCheck);
esp_task_wdt_add(Task_SerialCfg);
esp_task_wdt_add(Task_StreamTelemetry);
esp_task_wdt_add(Task_SysLed);
esp_task_wdt_add(Task_WiFiWatchdog);
esp_task_wdt_reset(); /* reset wdg */
SystemLog.AddEvent(LogLevel_Info, F("MCU configuration done"));
}
@ -140,7 +141,6 @@ void setup() {
void loop() {
/* reset wdg */
esp_task_wdt_reset();
delay(1000);
}
/* EOF */

View File

@ -1,151 +0,0 @@
/**
@file ExternalTemperatureSensor.cpp
@brief Library for external temperature sensor control
@author Miroslav Pivovarsky
Contact: miroslav.pivovarsky@gmail.com
@bug: no know bug
*/
#include "ExternalTemperatureSensor.h"
ExternalSensor ExternalTemperatureSensor(DHT_SENSOR_PIN, DHT_SENSOR_ENABLE, &SystemLog, &SystemConfig);
ExternalSensor::ExternalSensor(uint8_t i_pin, bool i_enable, Logs *i_log, Configuration *i_cfg) : DhtSensor(i_pin) {
Pin = i_pin;
SystemEnable = i_enable;
log = i_log;
config = i_cfg;
}
void ExternalSensor::Init() {
log->AddEvent(LogLevel_Info, F("Init external temperature sensor"));
Unit = (TemperatureSensorUnit_enum) config->LoadExternalTemperatureSensorUnit();
UserEnable = config->LoadExternalTemperatureSensorEnable();
//DhtSensor.setHumOffset(10);
//DhtSensor.setTempOffset(-3.5);
ReadSensorData();
}
String ExternalSensor::GetSensorStatus() {
String status = "";
if (false == SystemEnable) {
status = "Unsupport sensor";
} else if (false == UserEnable) {
status = "Sensor disabled";
} else {
status = "Detected: ";
SensorType = DhtSensor.getType();
switch (SensorType) {
case 0:
status += "not defined";
break;
case 11:
status += "DHT11";
break;
case 22:
status += "DHT22";
break;
case 23:
status += "DHT22";
break;
case 70:
status += "Sonoff Si7021";
break;
default:
status += "Unknown";
break;
}
}
return status;
}
void ExternalSensor::EnableSensor(bool i_enable) {
if (true == SystemEnable) {
UserEnable = i_enable;
config->SaveExternalTemperatureSensorEnable(UserEnable);
} else {
UserEnable = false;
config->SaveExternalTemperatureSensorEnable(UserEnable);
}
}
void ExternalSensor::ReadSensorData() {
if ((true == SystemEnable) && (true == UserEnable)) {
DhtSensor.read();
}
}
void ExternalSensor::SetUnit(TemperatureSensorUnit_enum i_unit) {
Unit = i_unit;
config->SaveExternalTemperatureSensorUnit(Unit);
}
float ExternalSensor::GetTemperature() {
float temp = 0.0;
if ((true == SystemEnable) && (true == UserEnable)) {
if (Unit == TEMPERATURE_UNIT_CELSIUS) {
temp = DhtSensor.getTemperature();
} else if (Unit == TEMPERATURE_UNIT_FAHRENHEIT) {
temp = DhtSensor.getTemperature() * 9.0 / 5.0 + 32.0;
}
}
return temp;
}
float ExternalSensor::GetHumidity() {
if ((true == SystemEnable) && (true == UserEnable)) {
return DhtSensor.getHumidity();
} else {
return 0.0;
}
}
String ExternalSensor::GetTemperatureString() {
String temp = "";
if (false == SystemEnable) {
temp = "Unsupport";
} else if ((false == UserEnable) || (false == SystemEnable)) {
temp = "Disabled";
} else {
if (Unit == TEMPERATURE_UNIT_CELSIUS) {
temp = String(GetTemperature(), 1) + " °C";
} else if (Unit == TEMPERATURE_UNIT_FAHRENHEIT) {
temp = String(GetTemperature(), 1) + " °F";
}
}
return temp;
}
String ExternalSensor::GetHumidityString() {
String hum = "";
if (false == SystemEnable) {
hum = "Unsupport";
} else if ((false == UserEnable) || (false == SystemEnable)) {
hum = "Disabled";
} else {
hum = String(GetHumidity(), 1) + " %";
}
return hum;
}
bool ExternalSensor::GetUserEnableSensor() {
return UserEnable;
}
TemperatureSensorUnit_enum ExternalSensor::GetTemperatureUnit() {
return Unit;
}
/* EOF */

View File

@ -1,59 +0,0 @@
/**
@file ExternalTemperatureSensor.h
@brief Library for external temperature sensor control
@author Miroslav Pivovarsky
Contact: miroslav.pivovarsky@gmail.com
@bug: no know bug
*/
#pragma once
#include <Arduino.h>
#include "log.h"
#include "mcu_cfg.h"
#include "module_templates.h"
#include <dhtnew.h>
#include "cfg.h"
#include "ExternalTemperatureSensorTypes.h"
class Logs;
class Configuration;
class ExternalSensor {
private:
TemperatureSensorUnit_enum Unit; ///< unit number
DHTNEW DhtSensor; ///< DHT sensor object
uint8_t Pin; ///< pin number
bool SystemEnable; ///< system enable flag
bool UserEnable; ///< user enable flag
uint8_t SensorType; ///< sensor type
Logs *log; ///< log object
Configuration *config; ///< configuration object
public:
ExternalSensor(uint8_t, bool, Logs *, Configuration *);
~ExternalSensor(){};
void Init();
String GetSensorStatus();
void EnableSensor(bool);
void ReadSensorData();
void SetUnit(TemperatureSensorUnit_enum);
float GetTemperature();
float GetHumidity();
String GetTemperatureString();
String GetHumidityString();
bool GetUserEnableSensor();
TemperatureSensorUnit_enum GetTemperatureUnit();
};
extern ExternalSensor ExternalTemperatureSensor;
/* EOF */

View File

@ -1,19 +0,0 @@
/**
@file connect_types.h
@brief Here are defined types for communication with prusa connect backend
@author Miroslav Pivovarsky
Contact: miroslav.pivovarsky@gmail.com
@bug: no know bug
*/
#pragma once
enum TemperatureSensorUnit_enum {
TEMPERATURE_UNIT_CELSIUS = 0, ///< Celsius
TEMPERATURE_UNIT_FAHRENHEIT = 1 ///< Fahrenheit
};
/* EOF */

File diff suppressed because it is too large Load Diff

View File

@ -10,7 +10,8 @@
@bug: no know bug
*/
#pragma once
#ifndef _WEB_PAGE_ICONS_H_
#define _WEB_PAGE_ICONS_H_
/* ------------------------------------------------------------------------------------------------------------ */
const char esp32_cam_logo_svg[] PROGMEM = R"rawliteral(
@ -88,4 +89,7 @@ const char favicon_svg[] PROGMEM = R"rawliteral(
</svg>
)rawliteral";
#endif
/* EOF */

View File

@ -6,9 +6,6 @@
@author Miroslav Pivovarsky
Contact: miroslav.pivovarsky@gmail.com
https://github.com/espressif/esp32-camera
@bug: no know bug
*/
#include "camera.h"
@ -22,33 +19,12 @@ Camera SystemCamera(&SystemConfig, &SystemLog, FLASH_GPIO_NUM);
@param uint8_t - flash pin
@return none
*/
Camera::Camera(Configuration* i_conf, Logs* i_log, int8_t i_FlashPin) {
Camera::Camera(Configuration* i_conf, Logs* i_log, uint8_t i_FlashPin) {
config = i_conf;
log = i_log;
CameraFlashPin = i_FlashPin;
StreamOnOff = false;
frameBufferSemaphore = xSemaphoreCreateMutex();
/* Allocate memory for the frame buffer */
FrameBufferDuplicate = (camera_fb_t*)heap_caps_malloc(sizeof(camera_fb_t), MALLOC_CAP_SPIRAM);
if (FrameBufferDuplicate != NULL) {
memset(FrameBufferDuplicate, 0, sizeof(camera_fb_t));
FrameBufferDuplicate->buf = NULL;
}
/* Allocate memory for the frame buffer */
FrameBufferExif = (camera_fb_t*)heap_caps_malloc(sizeof(camera_fb_t), MALLOC_CAP_SPIRAM);
if (FrameBufferExif != NULL) {
memset(FrameBufferExif, 0, sizeof(camera_fb_t));
FrameBufferExif->buf = NULL;
}
StreamSendingPhoto = false;
PhotoExifData.header = NULL;
PhotoExifData.len = 0;
PhotoExifData.offset = 0;
PhotoSending = false;
CameraCaptureFailedCounter = 0;
}
/**
@ -59,21 +35,13 @@ Camera::Camera(Configuration* i_conf, Logs* i_log, int8_t i_FlashPin) {
void Camera::Init() {
log->AddEvent(LogLevel_Info, F("Init camera lib"));
#if (true == ENABLE_CAMERA_FLASH)
log->AddEvent(LogLevel_Info, F("Init GPIO"));
#if (true == CAMERA_FLASH_PWM_CTRL)
ledcAttach(FLASH_GPIO_NUM, FLASH_PWM_FREQ, FLASH_PWM_RESOLUTION);
#elif (true == CAMERA_FLASH_DIGITAL_CTRL)
pinMode(FLASH_GPIO_NUM, OUTPUT);
digitalWrite(FLASH_GPIO_NUM, LOW);
#endif
SetFlashStatus(false);
#endif
ledcSetup(FLASH_PWM_CHANNEL, FLASH_PWM_FREQ, FLASH_PWM_RESOLUTION);
ledcAttachPin(FLASH_GPIO_NUM, FLASH_PWM_CHANNEL);
ledcWrite(FLASH_PWM_CHANNEL, FLASH_OFF_STATUS);
InitCameraModule();
ApplyCameraCfg();
GetCameraModel();
}
/**
@ -84,9 +52,7 @@ void Camera::Init() {
void Camera::InitCameraModule() {
log->AddEvent(LogLevel_Info, F("Init camera module"));
/* Turn-off the 'brownout detector' */
#if (true == ENABLE_BROWN_OUT_DETECTION)
WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0);
#endif
esp_err_t err;
CameraConfig.ledc_channel = LEDC_CHANNEL_0;
@ -107,7 +73,7 @@ void Camera::InitCameraModule() {
CameraConfig.pin_sccb_scl = SIOC_GPIO_NUM;
CameraConfig.pin_pwdn = PWDN_GPIO_NUM;
CameraConfig.pin_reset = RESET_GPIO_NUM;
CameraConfig.xclk_freq_hz = 15000000; // or 3000000; 16500000; 20000000
CameraConfig.xclk_freq_hz = 16500000; // or 3000000; 16500000; 20000000
CameraConfig.pixel_format = PIXFORMAT_JPEG; /* YUV422,GRAYSCALE,RGB565,JPEG */
/* OV2640
@ -118,21 +84,13 @@ void Camera::InitCameraModule() {
FRAMESIZE_XGA (1024 x 768)
FRAMESIZE_SXGA (1280 x 1024)
FRAMESIZE_UXGA (1600 x 1200)
CAMERA_GRAB_WHEN_EMPTY - Fills buffers when they are empty. Less resources but first 'fb_count' frames might be old
CAMERA_GRAB_LATEST - Except when 1 frame buffer is used, queue will always contain the last 'fb_count' frames
*/
CameraConfig.frame_size = TFrameSize; /* FRAMESIZE_ + QVGA|CIF|VGA|SVGA|XGA|SXGA|UXGA */
CameraConfig.jpeg_quality = PhotoQuality; /* 10-63 lower number means higher quality */
CameraConfig.fb_count = 1; /* picture frame buffer alocation */
CameraConfig.grab_mode = CAMERA_GRAB_LATEST; /* CAMERA_GRAB_WHEN_EMPTY or CAMERA_GRAB_LATEST */
#if (true == ENABLE_PSRAM)
CameraConfig.fb_location = CAMERA_FB_IN_PSRAM; /* CAMERA_FB_IN_PSRAM or CAMERA_FB_IN_DRAM */
#else
CameraConfig.fb_location = CAMERA_FB_IN_DRAM; /* CAMERA_FB_IN_PSRAM or CAMERA_FB_IN_DRAM */
#endif
CameraConfig.frame_size = TFrameSize; /* FRAMESIZE_ + QVGA|CIF|VGA|SVGA|XGA|SXGA|UXGA */
CameraConfig.jpeg_quality = PhotoQuality; /* 10-63 lower number means higher quality */
CameraConfig.fb_count = 1; /* picture frame buffer alocation */
CameraConfig.grab_mode = CAMERA_GRAB_LATEST; /* CAMERA_GRAB_WHEN_EMPTY or CAMERA_GRAB_LATEST */
if (CameraConfig.fb_location == CAMERA_FB_IN_DRAM) {
log->AddEvent(LogLevel_Verbose, F("Camera frame buffer location: DRAM"));
} else if (CameraConfig.fb_location == CAMERA_FB_IN_PSRAM) {
@ -144,10 +102,10 @@ void Camera::InitCameraModule() {
/* Camera init */
err = esp_camera_init(&CameraConfig);
if (err != ESP_OK) {
log->AddEvent(LogLevel_Warning, F("Camera init failed. Error: "), String(err, HEX));
log->AddEvent(LogLevel_Warning, "Camera init failed. Error: " + String(err, HEX));
log->AddEvent(LogLevel_Warning, F("Reset ESP32-cam!"));
ESP.restart();
}
}
}
/**
@ -180,7 +138,6 @@ void Camera::LoadCameraCfgFromEeprom() {
exposure_ctrl = config->LoadExposureCtrl();
CameraFlashEnable = config->LoadCameraFlashEnable();
CameraFlashTime = config->LoadCameraFlashTime();
imageExifRotation = config->LoadCameraImageExifRotation();
}
/**
@ -214,55 +171,24 @@ framesize_t Camera::TransformFrameSizeDataType(uint8_t i_data) {
break;
default:
ret = FRAMESIZE_QVGA;
log->AddEvent(LogLevel_Warning, F("Bad frame size. Set default value. "), String(i_data));
log->AddEvent(LogLevel_Warning, "Bad frame size. Set default value. " + String(i_data));
break;
}
}
return ret;
}
/**
@brief Function set photo sending status
@param bool i_data - true = on, false = off
@return none
*/
void Camera::SetPhotoSending(bool i_data) {
PhotoSending = i_data;
}
/**
@brief Function set flash status
@param bool i_data - true = on, false = off
@return none
*/
void Camera::SetFlashStatus(bool i_data) {
#if (true == ENABLE_CAMERA_FLASH)
/* PWM control of the FLASH */
#if (true == CAMERA_FLASH_PWM_CTRL)
if (true == i_data) {
ledcWrite(FLASH_GPIO_NUM, FLASH_ON_STATUS);
ledcWrite(FLASH_PWM_CHANNEL, FLASH_ON_STATUS);
} else if (false == i_data) {
ledcWrite(FLASH_GPIO_NUM, FLASH_OFF_STATUS);
ledcWrite(FLASH_PWM_CHANNEL, FLASH_OFF_STATUS);
}
/* Digital control of the FLASH */
#elif (true == CAMERA_FLASH_DIGITAL_CTRL)
if (true == i_data) {
digitalWrite(FLASH_GPIO_NUM, HIGH);
} else if (false == i_data) {
digitalWrite(FLASH_GPIO_NUM, LOW);
}
#endif
/* rgbLedWrite control of the FLASH */
#if (true == CAMERA_FLASH_NEOPIXEL)
if (true == i_data) {
rgbLedWrite(FLASH_NEOPIXEL_LED_PIN, RGB_BRIGHTNESS, RGB_BRIGHTNESS, RGB_BRIGHTNESS);
} else if (false == i_data) {
rgbLedWrite(FLASH_NEOPIXEL_LED_PIN, 0, 0, 0);
}
#endif
#endif
}
/**
@ -271,22 +197,12 @@ void Camera::SetFlashStatus(bool i_data) {
@return bool - true = on, false = off
*/
bool Camera::GetFlashStatus() {
#if (true == ENABLE_CAMERA_FLASH)
#if (true == CAMERA_FLASH_PWM_CTRL)
if (ledcRead(FLASH_GPIO_NUM) == FLASH_OFF_STATUS) {
if (ledcRead(FLASH_PWM_CHANNEL) == FLASH_OFF_STATUS) {
return false;
} else if (ledcRead(FLASH_GPIO_NUM) == FLASH_ON_STATUS) {
} else if (ledcRead(FLASH_PWM_CHANNEL) == FLASH_ON_STATUS) {
return true;
}
#elif (true == CAMERA_FLASH_DIGITAL_CTRL)
if (digitalRead(FLASH_GPIO_NUM) == LOW) {
return false;
} else if (digitalRead(FLASH_GPIO_NUM) == HIGH) {
return true;
}
#endif
#endif
return false;
}
@ -299,7 +215,7 @@ void Camera::ApplyCameraCfg() {
log->AddEvent(LogLevel_Info, F("Set camera CFG"));
/* sensor configuration */
sensor = esp_camera_sensor_get();
sensor_t* sensor = esp_camera_sensor_get();
sensor->set_brightness(sensor, brightness); // -2 to 2
sensor->set_contrast(sensor, contrast); // -2 to 2
sensor->set_saturation(sensor, saturation); // -2 to 2
@ -332,150 +248,71 @@ void Camera::ApplyCameraCfg() {
void Camera::ReinitCameraModule() {
esp_err_t err = esp_camera_deinit();
if (err != ESP_OK) {
log->AddEvent(LogLevel_Warning, F("Camera error deinit camera module. Error: "), String(err, HEX));
log->AddEvent(LogLevel_Warning, "Camera error deinit camera module. Error: " + String(err, HEX));
}
delay(100);
InitCameraModule();
ApplyCameraCfg();
}
/**
@brief Function for get camera model and type
@param void
@return none
*/
void Camera::GetCameraModel() {
log->AddEvent(LogLevel_Info, F("Get camera model and type"));
if (sensor == NULL) {
log->AddEvent(LogLevel_Error, F("Camera sensor is NULL"));
return;
}
camera_sensor_info_t *info = esp_camera_sensor_get_info(&sensor->id);
if (info == NULL) {
log->AddEvent(LogLevel_Error, F("Camera sensor info is NULL"));
return;
}
CameraType = (camera_pid_t) sensor->id.PID;
CameraName = info->name;
log->AddEvent(LogLevel_Info, F("Camera type: "), String(CameraType));
log->AddEvent(LogLevel_Info, F("Camera name: "), String(CameraName));
log->AddEvent(LogLevel_Info, F("Camera model: "), String(info->model));
log->AddEvent(LogLevel_Info, F("Camera PID: "), String(info->pid));
log->AddEvent(LogLevel_Info, F("Camera MAX framesize: "), String(info->max_size));
log->AddEvent(LogLevel_Info, F("Camera support jpeg: "), String(info->support_jpeg));
}
/**
@brief Capture Photo and Save it to string array
@param none
@return none
*/
void Camera::CapturePhoto() {
/* Check if photo is already sending */
if (true == PhotoSending) {
log->AddEvent(LogLevel_Info, F("Sending photo"));
return;
}
/* Check if stream is on */
if (false == StreamOnOff) {
if (!xSemaphoreTake(frameBufferSemaphore, portMAX_DELAY)) {
log->AddEvent(LogLevel_Error, F("Failed to take frame buffer semaphore"));
return;
}
CameraCaptureSuccess = false;
/* check flash, and enable FLASH LED */
if (true == CameraFlashEnable) {
SetFlashStatus(true);
delay(CameraFlashTime);
}
if (FrameBuffer) {
esp_camera_fb_return(FrameBuffer);
}
/* Capturing a training photo. Without this sequence, the camera will not obtain the current photo but photo from the previous cycle. */
FrameBuffer = esp_camera_fb_get();
if (FrameBuffer) {
esp_camera_fb_return(FrameBuffer);
log->AddEvent(LogLevel_Verbose, F("Camera capture training photo"));
} else {
esp_camera_fb_return(FrameBuffer);
log->AddEvent(LogLevel_Error, F("Camera capture failed training photo"));
//ReinitCameraModule();
}
int attempts = 0;
const int maxAttempts = 5;
PhotoExifData.header = NULL;
do {
log->AddEvent(LogLevel_Info, F("Taking photo..."));
FrameBuffer = esp_camera_fb_get();
if (!FrameBuffer) {
CameraCaptureFailedCounter++;
log->AddEvent(LogLevel_Error, F("Camera capture failed! photo. Attempt: "), String(CameraCaptureFailedCounter));
xSemaphoreGive(frameBufferSemaphore); // Release semaphore before returning
return;
}
char buf[150] = { '\0' };
uint8_t ControlFlag = (uint8_t)FrameBuffer->buf[15];
sprintf(buf, "The picture has been saved. Size: %d bytes, Photo resolution: %zu x %zu", FrameBuffer->len, FrameBuffer->width, FrameBuffer->height);
log->AddEvent(LogLevel_Info, buf);
if (ControlFlag != 0x00) {
log->AddEvent(LogLevel_Error, "Camera capture failed! flag: " + String(ControlFlag, HEX));
FrameBuffer->len = 0;
} else {
log->AddEvent(LogLevel_Info, F("Photo OK! "), String(ControlFlag, HEX));
CameraCaptureFailedCounter = 0;
/* generate exif header */
update_exif_from_cfg(imageExifRotation);
get_exif_header(FrameBuffer, &PhotoExifData.header, &PhotoExifData.len);
PhotoExifData.offset = get_jpeg_data_offset(FrameBuffer);
CameraCaptureSuccess = true;
if (PhotoExifData.header != NULL) {
log->AddEvent(LogLevel_Info, F("Exif header OK! Len: "), String(PhotoExifData.len));
} else {
log->AddEvent(LogLevel_Error, F("Exif header failed! "), String(PhotoExifData.len));
}
}
attempts++;
if (attempts >= maxAttempts) {
log->AddEvent(LogLevel_Error, F("Failed to capture a valid photo after max attempts"));
break;
}
} while (!(FrameBuffer->len > 100));
/* Disable flash */
if (true == CameraFlashEnable) {
SetFlashStatus(false);
}
xSemaphoreGive(frameBufferSemaphore);
} else {
/* Stream is on, set flag for sending photo */
if (xSemaphoreTake(frameBufferSemaphore, portMAX_DELAY)) {
StreamSendingPhoto = true;
/* check flash, and enable FLASH LED */
if (true == CameraFlashEnable) {
ledcWrite(FLASH_PWM_CHANNEL, FLASH_ON_STATUS);
delay(CameraFlashTime);
}
/* get train photo */
FrameBuffer = esp_camera_fb_get();
esp_camera_fb_return(FrameBuffer);
do {
log->AddEvent(LogLevel_Info, F("Taking photo..."));
/* capture final photo */
delay(5); // delay for camera stabilization. test it
FrameBuffer = esp_camera_fb_get();
if (!FrameBuffer) {
log->AddEvent(LogLevel_Error, F("Camera capture failed! photo"));
return;
} else {
/* copy photo from buffer to string array */
char buf[150] = { '\0' };
uint8_t ControlFlag = (uint8_t)FrameBuffer->buf[15];
sprintf(buf, "The picture has been saved. Size: %d bytes, Photo resolution: %zu x %zu", FrameBuffer->len, FrameBuffer->width, FrameBuffer->height);
log->AddEvent(LogLevel_Info, buf);
/* check corrupted photo */
if (ControlFlag != 0x00) {
log->AddEvent(LogLevel_Error, "Camera capture failed! photo " + String(ControlFlag, HEX));
FrameBuffer->len = 0;
} else {
log->AddEvent(LogLevel_Info, "Photo OK! " + String(ControlFlag, HEX));
}
esp_camera_fb_return(FrameBuffer);
}
/* check if photo is correctly saved */
} while (!(FrameBuffer->len > 100));
/* Disable flash */
if (true == CameraFlashEnable) {
delay(CameraFlashTime);
ledcWrite(FLASH_PWM_CHANNEL, FLASH_OFF_STATUS);
}
xSemaphoreGive(frameBufferSemaphore);
}
}
/* Reinit camera module if photo capture failed */
if (CameraCaptureFailedCounter > CAMERA_MAX_FAIL_CAPTURE) {
log->AddEvent(LogLevel_Error, F("Camera capture failed! photo max attempts"));
CameraCaptureFailedCounter = 0;
ReinitCameraModule();
}
}
/**
@ -496,112 +333,7 @@ void Camera::CaptureStream(camera_fb_t* i_buf) {
/* check if photo is correctly saved */
} while (!(FrameBuffer->len > 100));
/* check if the photo is rotated */
bool ExifStatus = false;
#if (true == CAMERA_EXIF_ROTATION_STREAM)
if (1 != imageExifRotation) { /* 1 = image rotation 0 degree */
/* generate exif header */
update_exif_from_cfg(imageExifRotation);
get_exif_header(FrameBuffer, &PhotoExifData.header, &PhotoExifData.len);
PhotoExifData.offset = get_jpeg_data_offset(FrameBuffer);
if (PhotoExifData.header != NULL) {
/* memory allocation release */
if (FrameBufferExif != NULL) {
if (FrameBufferExif->buf != NULL) {
free(FrameBufferExif->buf);
FrameBufferExif->buf = NULL; /* Set to NULL after freeing */
}
free(FrameBufferExif);
FrameBufferExif = NULL; /* Set to NULL after freeing */
}
/* Allocate memory for the duplicate frame structure */
FrameBufferExif = (camera_fb_t*)heap_caps_malloc(sizeof(camera_fb_t), MALLOC_CAP_SPIRAM);
/* Calculate the total size of the buffer */
size_t totalSize = PhotoExifData.len + FrameBuffer->len - PhotoExifData.offset;
/* Allocate memory for the image data */
FrameBufferExif->buf = (uint8_t*)heap_caps_malloc(totalSize, MALLOC_CAP_SPIRAM);
if (FrameBufferExif->buf == NULL) {
log->AddEvent(LogLevel_Error, F("Failed to allocate memory for EXIF buffer"));
return;
}
/* copy the EXIF data to the buffer */
memcpy(FrameBufferExif->buf, PhotoExifData.header, PhotoExifData.len);
/* copy the image data to the buffer */
memcpy(FrameBufferExif->buf + PhotoExifData.len, FrameBuffer->buf + PhotoExifData.offset, FrameBuffer->len - PhotoExifData.offset);
/* Set the length of the buffer */
FrameBufferExif->len = totalSize;
*i_buf = *FrameBufferExif;
ExifStatus = true;
} else {
/* copy the frame buffer to the buffer */
*i_buf = *FrameBuffer;
}
} else {
/* copy the frame buffer to the buffer */
*i_buf = *FrameBuffer;
}
#else
*i_buf = *FrameBuffer;
#endif
/* copy the frame buffer to the duplicate frame buffer. For sending photo to Prusa Connect */
if (false == StreamSendingPhoto) {
/* memory allocation release */
if (FrameBufferDuplicate != NULL) {
if (FrameBufferDuplicate->buf != NULL) {
free(FrameBufferDuplicate->buf);
FrameBufferDuplicate->buf = NULL; /* Set to NULL after freeing */
}
free(FrameBufferDuplicate);
FrameBufferDuplicate = NULL; /* Set to NULL after freeing */
}
/* Allocate memory for the duplicate frame structure */
FrameBufferDuplicate = (camera_fb_t*)heap_caps_malloc(sizeof(camera_fb_t), MALLOC_CAP_SPIRAM);
/* Copy the metadata */
if (true == ExifStatus) {
memcpy(FrameBufferDuplicate, FrameBufferExif, sizeof(camera_fb_t));
} else {
memcpy(FrameBufferDuplicate, FrameBuffer, sizeof(camera_fb_t));
}
/* Allocate memory for the image data */
if (true == ExifStatus) {
FrameBufferDuplicate->buf = (uint8_t*)heap_caps_malloc(FrameBufferExif->len, MALLOC_CAP_SPIRAM);
} else {
FrameBufferDuplicate->buf = (uint8_t*)heap_caps_malloc(FrameBuffer->len, MALLOC_CAP_SPIRAM);
}
/* Check if memory allocation was successful */
if (!FrameBufferDuplicate->buf) {
/* Handle error */
free(FrameBufferDuplicate);
Serial.println("Failed to allocate memory for the duplicate frame buffer");
} else {
/* Copy the image data */
if (true == ExifStatus) {
memcpy(FrameBufferDuplicate->buf, FrameBufferExif->buf, FrameBufferExif->len);
} else {
memcpy(FrameBufferDuplicate->buf, FrameBuffer->buf, FrameBuffer->len);
}
}
}
xSemaphoreGive(frameBufferSemaphore);
}
}
@ -622,10 +354,7 @@ void Camera::CaptureReturnFrameBuffer() {
*/
void Camera::SetStreamStatus(bool i_status) {
StreamOnOff = i_status;
if (FrameBuffer) {
esp_camera_fb_return(FrameBuffer);
}
log->AddEvent(LogLevel_Info, F("Camera video stream: "), String(StreamOnOff));
log->AddEvent(LogLevel_Info, "Camera video stream: " + String(StreamOnOff));
}
/**
@ -637,10 +366,6 @@ bool Camera::GetStreamStatus() {
return StreamOnOff;
}
bool Camera::GetCameraCaptureSuccess() {
return CameraCaptureSuccess;
}
/**
@brief Set Frame Size
@param uint16_t - frame size
@ -687,15 +412,6 @@ void Camera::StreamClearFrameData() {
StreamAverageSize = 0;
}
/**
@brief Set Sending Photo for Stream
@param bool - sending photo
@return none
*/
void Camera::StreamSetSendingPhoto(bool i_data) {
StreamSendingPhoto = i_data;
}
/**
@brief Get Photo
@param none
@ -718,24 +434,6 @@ camera_fb_t* Camera::GetPhotoFb() {
return FrameBuffer;
}
/**
@brief Get Photo Frame Buffer Duplicate
@param none
@return camera_fb_t* - photo frame buffer duplicate
*/
camera_fb_t* Camera::GetPhotoFbDuplicate() {
return FrameBufferDuplicate;
}
/**
@brief Get Photo Exif Data
@param none
@return PhotoExifData_t* - photo exif data
*/
PhotoExifData_t* Camera::GetPhotoExifData() {
return &PhotoExifData;
}
/**
@brief Copy Photo
@param camera_fb_t* - pointer to camera_fb_t
@ -766,24 +464,11 @@ void Camera::CopyPhoto(String* i_data) {
* @param i_to - end index
*/
void Camera::CopyPhoto(String* i_data, int i_from, int i_to) {
*i_data = "";
for (int i = i_from; i < i_to; i++) {
*i_data += (char)FrameBuffer->buf[i];
Photo = "";
for (size_t i = i_from; i < i_to; i++) {
Photo += (char)FrameBuffer->buf[i];
}
}
/**
* @brief Copy photo from frame buffer to char array with range
*
* @param i_data - pointer to char array
* @param i_from - start index
* @param i_to - end index
*/
void Camera::CopyPhoto(char* i_data, int i_from, int i_to) {
int length = i_to - i_from;
memcpy(i_data, FrameBuffer->buf + i_from, length);
i_data[length + 1] = '\0';
*i_data = Photo;
}
/**
@ -792,8 +477,8 @@ void Camera::CopyPhoto(char* i_data, int i_from, int i_to) {
* @return int - photo size
*/
int Camera::GetPhotoSize() {
log->AddEvent(LogLevel_Verbose, F("Photo size: "), String(FrameBuffer->len));
return (int)FrameBuffer->len;
log->AddEvent(LogLevel_Verbose, "Photo size: " + String(FrameBuffer->len));
return (int) FrameBuffer->len;
}
/**
@ -1037,11 +722,6 @@ void Camera::SetCameraFlashTime(uint16_t i_data) {
CameraFlashTime = i_data;
}
void Camera::SetCameraImageRotation(uint8_t i_data) {
config->SaveCameraImageExifRotation(i_data);
imageExifRotation = i_data;
}
/**
@brief Get Photo Quality
@param none
@ -1074,35 +754,35 @@ uint8_t Camera::GetFrameSize() {
* @return uint16_t
*/
uint16_t Camera::GetFrameSizeWidth() {
uint16_t ret = 0;
switch (FrameSize) {
case 0:
ret = 320;
break;
case 1:
ret = 352;
break;
case 2:
ret = 640;
break;
case 3:
ret = 800;
break;
case 4:
ret = 1024;
break;
case 5:
ret = 1280;
break;
case 6:
ret = 1600;
break;
default:
ret = 320;
break;
uint16_t ret = 0;
switch (FrameSize) {
case 0:
ret = 320;
break;
case 1:
ret = 352;
break;
case 2:
ret = 640;
break;
case 3:
ret = 800;
break;
case 4:
ret = 1024;
break;
case 5:
ret = 1280;
break;
case 6:
ret = 1600;
break;
default:
ret = 320;
break;
}
return ret;
}
@ -1140,7 +820,7 @@ uint16_t Camera::GetFrameSizeHeight() {
case 5:
ret = 1024;
break;
case 6:
case 6:
ret = 1200;
break;
default:
@ -1331,8 +1011,4 @@ uint16_t Camera::GetCameraFlashTime() {
return CameraFlashTime;
}
uint8_t Camera::GetCameraImageRotation() {
return imageExifRotation;
}
/* EOF */

View File

@ -9,29 +9,21 @@
@bug: no know bug
*/
#pragma once
#ifndef _CAMERA_H_
#define _CAMERA_H_
#include "esp_camera.h"
#include "esp_timer.h"
#include "img_converters.h"
#include "soc/soc.h"
#include "soc/rtc_cntl_reg.h"
#include "micro_sd.h"
#include "log.h"
#include "cfg.h"
#include "exif.h"
#include "module_templates.h"
#include "Camera_cfg.h"
#include "Arduino.h"
#include "mcu_cfg.h"
#include "var.h"
class Configuration;
struct PhotoExifData_t {
const uint8_t *header;
size_t len;
size_t offset;
};
#include "log.h"
class Camera {
private:
@ -57,29 +49,17 @@ private:
bool exposure_ctrl; ///< exposure control
bool CameraFlashEnable; ///< enable/disable camera flash function
uint16_t CameraFlashTime; ///< camera fash duration time
int8_t CameraFlashPin; ///< GPIO pin for LED
uint8_t CameraFlashPin; ///< GPIO pin for LED
framesize_t TFrameSize; ///< framesize_t type for camera module
uint8_t imageExifRotation; ///< image rotation. 0 degree: value 1, 90 degree: value 6, 180 degree: value 3, 270 degree: value 8
bool CameraCaptureSuccess; ///< camera capture success
bool PhotoSending; ///< photo sending
/* OV2640 camera module pinout and cfg*/
camera_config_t CameraConfig; ///< camera configuration
camera_fb_t *FrameBuffer; ///< frame buffer
camera_fb_t *FrameBufferDuplicate; ///< frame buffer duplicate
camera_fb_t *FrameBufferExif; ///< frame buffer with exif data
sensor_t* sensor; ///< sensor
String Photo; ///< photo in string format
bool StreamOnOff; ///< stream on/off
bool StreamSendingPhoto; ///< sending photo to Prusa Connect during stream
SemaphoreHandle_t frameBufferSemaphore; ///< semaphore for frame buffer
float StreamAverageFps; ///< stream average fps
uint16_t StreamAverageSize; ///< stream average size
PhotoExifData_t PhotoExifData; ///< photo exif data
uint8_t CameraCaptureFailedCounter; ///< camera capture failed counter
camera_pid_t CameraType; ///< camera type
String CameraName; ///< camera name
Configuration *config; ///< pointer to Configuration object
Logs *log; ///< pointer to Logs object
@ -87,38 +67,31 @@ private:
void InitCameraModule();
public:
Camera(Configuration*, Logs*, int8_t);
Camera(Configuration*, Logs*, uint8_t);
~Camera(){};
void Init();
void ApplyCameraCfg();
void LoadCameraCfgFromEeprom();
void ReinitCameraModule();
void GetCameraModel();
void CapturePhoto();
void CaptureStream(camera_fb_t *);
void CaptureReturnFrameBuffer();
void SetStreamStatus(bool);
bool GetStreamStatus();
bool GetCameraCaptureSuccess();
void StreamSetFrameSize(uint16_t);
void StreamSetFrameFps(float);
uint16_t StreamGetFrameAverageSize();
float StreamGetFrameAverageFps();
void StreamClearFrameData();
void StreamSetSendingPhoto(bool);
void CopyPhoto(camera_fb_t *);
void CopyPhoto(String*);
void CopyPhoto(String*, int, int);
void CopyPhoto(char*, int, int);
int GetPhotoSize();
String GetPhoto();
camera_fb_t *GetPhotoFb();
camera_fb_t* GetPhotoFbDuplicate();
PhotoExifData_t * GetPhotoExifData();
framesize_t TransformFrameSizeDataType(uint8_t);
void SetPhotoSending(bool);
void SetFlashStatus(bool);
bool GetFlashStatus();
@ -145,7 +118,6 @@ public:
void SetExposureCtrl(bool);
void SetCameraFlashEnable(bool);
void SetCameraFlashTime(uint16_t);
void SetCameraImageRotation(uint8_t);
uint8_t GetPhotoQuality();
uint8_t GetFrameSize();
@ -171,9 +143,10 @@ public:
bool GetExposureCtrl();
bool GetCameraFlashEnable();
uint16_t GetCameraFlashTime();
uint8_t GetCameraImageRotation();
};
extern Camera SystemCamera; ///< Camera object
#endif
/* EOF */

View File

@ -29,7 +29,7 @@ Configuration::Configuration(Logs* i_log) {
@return none
*/
void Configuration::Init() {
Log->AddEvent(LogLevel_Info, F("Init cfg module: "), String(EEPROM_SIZE));
Log->AddEvent(LogLevel_Info, "Init cfg module: " + String(EEPROM_SIZE));
//EEPROM.begin(EEPROM_SIZE);
/* check, when it is first MCU start. If yes, then set default CFG */
@ -83,14 +83,7 @@ void Configuration::ReadCfg() {
LoadGainCtrl();
LoadAgcGain();
LoadPrusaConnectHostname();
LoadNetworkIpMethod();
LoadNetworkIp();
LoadNetworkMask();
LoadNetworkGateway();
LoadNetworkDns();
LoadCameraImageExifRotation();
LoadTimeLapseFunctionStatus();
Log->AddEvent(LogLevel_Info, F("Active WiFi client cfg: "), String(CheckActifeWifiCfgFlag() ? "true" : "false"));
Log->AddEvent(LogLevel_Info, "Active WiFi client cfg: " + String(CheckActifeWifiCfgFlag() ? "true" : "false"));
Log->AddEvent(LogLevel_Info, F("Load CFG from EEPROM done"));
}
@ -100,14 +93,14 @@ void Configuration::ReadCfg() {
@return bool - status
*/
bool Configuration::CheckFirstMcuStart() {
Log->AddEvent(LogLevel_Info, F("Read FirstMcuStart FLAG"));
Log->AddEvent(LogLevel_Info, F("Read FirstMcuStart: "));
uint8_t flag = EEPROM.read(EEPROM_ADDR_FIRST_MCU_START_FLAG_START);
if (CFG_FIRST_MCU_START_NAK == flag) {
Log->AddEvent(LogLevel_Info, F("It's not first start MCU: "), String(flag));
Log->AddEvent(LogLevel_Info, "It's not first start MCU: " + String(flag));
return false;
} else {
Log->AddEvent(LogLevel_Warning, F("First start MCU!: "), String(flag));
Log->AddEvent(LogLevel_Warning, "First start MCU!: " + String(flag));
return true;
}
@ -120,7 +113,7 @@ bool Configuration::CheckFirstMcuStart() {
@return none
*/
void Configuration::SaveFirstMcuStartFlag(uint8_t i_data) {
Log->AddEvent(LogLevel_Info, F("Save first MCU start flag: "), String(i_data));
Log->AddEvent(LogLevel_Info, "Save first MCU start flag: " + String(i_data));
SaveUint8(EEPROM_ADDR_FIRST_MCU_START_FLAG_START, i_data);
}
@ -173,10 +166,6 @@ void Configuration::DefaultCfg() {
SaveNetworkMask(FACTORY_CFG_NETWORK_STATIC_MASK);
SaveNetworkGateway(FACTORY_CFG_NETWORK_STATIC_GATEWAY);
SaveNetworkDns(FACTORY_CFG_NETWORK_STATIC_DNS);
SaveCameraImageExifRotation(FACTORY_CFG_IMAGE_EXIF_ROTATION);
SaveTimeLapseFunctionStatus(FACTORY_CFG_TIMELAPS_ENABLE);
SaveExternalTemperatureSensorEnable(FACTORY_CFG_ENABLE_EXT_SENSOR);
SaveExternalTemperatureSensorUnit(FACTORY_CFG_EXT_SENSOR_UNIT);
Log->AddEvent(LogLevel_Warning, F("+++++++++++++++++++++++++++"));
}
@ -187,7 +176,7 @@ void Configuration::DefaultCfg() {
*/
bool Configuration::CheckActifeWifiCfgFlag() {
uint8_t flag = EEPROM.read(EEPROM_ADDR_WIFI_ACTIVE_FLAG_START);
Log->AddEvent(LogLevel_Verbose, F("Read ActifeWifiCfgFlag: "), String(flag));
Log->AddEvent(LogLevel_Verbose, "Read ActifeWifiCfgFlag: " + String(flag));
if (CFG_WIFI_SETTINGS_SAVED == flag) {
return true;
@ -210,7 +199,7 @@ void Configuration::CheckResetCfg() {
/* wait 10s to pressed reset pin */
uint8_t i = 0;
for (i = 0; i < (CFG_RESET_TIME_WAIT / CFG_RESET_LOOP_DELAY); i++) {
Log->AddEvent(LogLevel_Verbose, F("Reset pin status: "), String(ResetPinStatus));
Log->AddEvent(LogLevel_Verbose, "Reset pin status: " + String(ResetPinStatus));
if (ResetPinStatus == HIGH) {
break;
}
@ -225,15 +214,14 @@ void Configuration::CheckResetCfg() {
/* wait for ungrounded reset pin, and binking led */
while (digitalRead(CFG_RESET_PIN) == LOW) {
digitalWrite(CFG_RESET_LED_PIN, CFG_RESET_LED_LEVEL_ON);
analogWrite(FLASH_GPIO_NUM, 20);
delay(100);
digitalWrite(CFG_RESET_LED_PIN, !CFG_RESET_LED_LEVEL_ON);
analogWrite(FLASH_GPIO_NUM, 0);
delay(100);
}
/* turn off LED, reset cfg, reset MCU */
digitalWrite(CFG_RESET_LED_PIN, !CFG_RESET_LED_LEVEL_ON);
analogWrite(FLASH_GPIO_NUM, 0);
DefaultCfg();
ESP.restart();
@ -256,10 +244,10 @@ void Configuration::GetFingerprint() {
//String Random = String(esp_random());
String encoded = base64::encode(Id + " " + WiFiMacAddress);
SaveFingerprint(encoded);
Log->AddEvent(LogLevel_Verbose, F("UniqueID: "), Id);
Log->AddEvent(LogLevel_Verbose, F("WiFi MAC: "), WiFiMacAddress);
Log->AddEvent(LogLevel_Verbose, "UniqueID: " + Id);
Log->AddEvent(LogLevel_Verbose, "WiFi MAC: " + WiFiMacAddress);
//Log->AddEvent(LogLevel_Verbose, "Random number: " + Random);
Log->AddEvent(LogLevel_Warning, F("Calculated device fingerprint: "), encoded);
Log->AddEvent(LogLevel_Warning, "Calculated device fingerprint: " + encoded);
}
/**
@ -437,7 +425,7 @@ String Configuration::LoadIpAddress(uint16_t address) {
@return none
*/
void Configuration::SaveRefreshInterval(uint8_t i_interval) {
Log->AddEvent(LogLevel_Verbose, F("Save RefreshInterval: "), String(i_interval));
Log->AddEvent(LogLevel_Verbose, "Save RefreshInterval: " + String(i_interval));
SaveUint8(EEPROM_ADDR_REFRESH_INTERVAL_START, i_interval);
}
@ -447,7 +435,7 @@ void Configuration::SaveRefreshInterval(uint8_t i_interval) {
@return none
*/
void Configuration::SaveToken(String i_token) {
Log->AddEvent(LogLevel_Verbose, F("Save Token["), String(i_token.length()) + "]: " + i_token);
Log->AddEvent(LogLevel_Verbose, "Save Token[" + String(i_token.length()) + "]: " + i_token);
SaveString(EEPROM_ADDR_TOKEN_START, EEPROM_ADDR_TOKEN_LENGTH, i_token);
}
@ -457,7 +445,7 @@ void Configuration::SaveToken(String i_token) {
@return none
*/
void Configuration::SaveFingerprint(String i_fingerprint) {
Log->AddEvent(LogLevel_Verbose, F("Save Fingerprint["), String(i_fingerprint.length()) + "]: " + i_fingerprint);
Log->AddEvent(LogLevel_Verbose, "Save Fingerprint[" + String(i_fingerprint.length()) + "]: " + i_fingerprint);
SaveString(EEPROM_ADDR_FINGERPRINT_START, EEPROM_ADDR_FINGERPRINT_LENGTH, i_fingerprint);
}
@ -467,7 +455,7 @@ void Configuration::SaveFingerprint(String i_fingerprint) {
@return none
*/
void Configuration::SavePhotoQuality(uint8_t i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save PhotoQuality: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save PhotoQuality: " + String(i_data));
SaveUint8(EEPROM_ADDR_PHOTO_QUALITY_START, i_data);
}
@ -477,7 +465,7 @@ void Configuration::SavePhotoQuality(uint8_t i_data) {
@return none
*/
void Configuration::SaveFrameSize(uint8_t i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save FrameSize: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save FrameSize: " + String(i_data));
SaveUint8(EEPROM_ADDR_FRAMESIZE_START, i_data);
}
@ -487,7 +475,7 @@ void Configuration::SaveFrameSize(uint8_t i_data) {
@return none
*/
void Configuration::SaveBrightness(int8_t i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save Brightness: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save Brightness: " + String(i_data));
SaveInt8(EEPROM_ADDR_BRIGHTNESS_START, i_data);
}
@ -497,7 +485,7 @@ void Configuration::SaveBrightness(int8_t i_data) {
@return none
*/
void Configuration::SaveContrast(int8_t i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save Contrast: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save Contrast: " + String(i_data));
SaveInt8(EEPROM_ADDR_CONTRAST_START, i_data);
}
@ -507,7 +495,7 @@ void Configuration::SaveContrast(int8_t i_data) {
@return none
*/
void Configuration::SaveSaturation(int8_t i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save Saturation: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save Saturation: " + String(i_data));
SaveInt8(EEPROM_ADDR_SATURATION_START, i_data);
}
@ -517,7 +505,7 @@ void Configuration::SaveSaturation(int8_t i_data) {
@return none
*/
void Configuration::SaveHmirror(bool i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save Hmirror: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save Hmirror: " + String(i_data));
SaveBool(EEPROM_ADDR_HMIRROR_START, i_data);
}
@ -527,7 +515,7 @@ void Configuration::SaveHmirror(bool i_data) {
@return none
*/
void Configuration::SaveVflip(bool i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save vflip: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save vflip: " + String(i_data));
SaveBool(EEPROM_ADDR_VFLIP_START, i_data);
}
@ -537,7 +525,7 @@ void Configuration::SaveVflip(bool i_data) {
@return none
*/
void Configuration::SaveLensCorrect(bool i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save lensc: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save lensc: " + String(i_data));
SaveBool(EEPROM_ADDR_LENSC_START, i_data);
}
@ -547,7 +535,7 @@ void Configuration::SaveLensCorrect(bool i_data) {
@return none
*/
void Configuration::SaveExposureCtrl(bool i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save exposure_ctrl: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save exposure_ctrl: " + String(i_data));
SaveBool(EEPROM_ADDR_EXPOSURE_CTRL_START, i_data);
}
@ -557,7 +545,7 @@ void Configuration::SaveExposureCtrl(bool i_data) {
@return none
*/
void Configuration::SaveAwb(bool i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save awb: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save awb: " + String(i_data));
SaveBool(EEPROM_ADDR_AWB_ENABLE_START, i_data);
}
@ -567,7 +555,7 @@ void Configuration::SaveAwb(bool i_data) {
@return none
*/
void Configuration::SaveAwbGain(bool i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save awb_gain: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save awb_gain: " + String(i_data));
Configuration::SaveBool(EEPROM_ADDR_AWB_GAIN_ENABLE_START, i_data);
}
@ -577,7 +565,7 @@ void Configuration::SaveAwbGain(bool i_data) {
@return none
*/
void Configuration::SaveAwbMode(uint8_t i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save awb_mode: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save awb_mode: " + String(i_data));
SaveUint8(EEPROM_ADDR_AWB_MODE_ENABLE_START, i_data);
}
@ -587,7 +575,7 @@ void Configuration::SaveAwbMode(uint8_t i_data) {
@return none
*/
void Configuration::SaveBpc(bool i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save bpc: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save bpc: " + String(i_data));
SaveBool(EEPROM_ADDR_BPC_ENABLE_START, i_data);
}
@ -597,7 +585,7 @@ void Configuration::SaveBpc(bool i_data) {
@return none
*/
void Configuration::SaveWpc(bool i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save wpc: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save wpc: " + String(i_data));
SaveBool(EEPROM_ADDR_WPC_ENABLE_START, i_data);
}
@ -607,7 +595,7 @@ void Configuration::SaveWpc(bool i_data) {
@return none
*/
void Configuration::SaveRawGama(bool i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save raw_gama: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save raw_gama: " + String(i_data));
SaveBool(EEPROM_ADDR_RAW_GAMA_ENABLE_START, i_data);
}
@ -617,7 +605,7 @@ void Configuration::SaveRawGama(bool i_data) {
@return none
*/
void Configuration::SaveWifiSsid(String i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save WI-FI SSID["), String(i_data.length()) + "]: " + i_data);
Log->AddEvent(LogLevel_Verbose, "Save WI-FI SSID[" + String(i_data.length()) + "]: " + i_data);
SaveString(EEPROM_ADDR_WIFI_SSID_START, EEPROM_ADDR_WIFI_SSID_LENGTH, i_data);
}
@ -628,7 +616,7 @@ void Configuration::SaveWifiSsid(String i_data) {
*/
void Configuration::SaveWifiPassword(String i_data) {
//Log->AddEvent(LogLevel_Verbose, "Save WI-FI password[" + String(i_data.length()) + "]: " + i_data); /* SENSITIVE DATA! */
Log->AddEvent(LogLevel_Verbose, F("Save WI-FI password["), String(i_data.length()) + "]");
Log->AddEvent(LogLevel_Verbose, "Save WI-FI password[" + String(i_data.length()) + "]");
SaveString(EEPROM_ADDR_WIFI_PASSWORD_START, EEPROM_ADDR_WIFI_PASSWORD_LENGTH, i_data);
}
@ -638,7 +626,7 @@ void Configuration::SaveWifiPassword(String i_data) {
@return none
*/
void Configuration::SaveWifiCfgFlag(uint8_t i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save active wifi cfg flag: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save active wifi cfg flag: " + String(i_data));
SaveUint8(EEPROM_ADDR_WIFI_ACTIVE_FLAG_START, i_data);
}
@ -648,7 +636,7 @@ void Configuration::SaveWifiCfgFlag(uint8_t i_data) {
@return none
*/
void Configuration::SaveEnableServiceAp(bool i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save Enable/disable service AP: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save Enable/disable service AP: " + String(i_data));
SaveBool(EEPROM_ADDR_SERVICE_AP_ENABLE_START, i_data);
}
@ -658,10 +646,11 @@ void Configuration::SaveEnableServiceAp(bool i_data) {
@return none
*/
void Configuration::SaveBasicAuthUsername(String i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save username BasicAuth["), String(i_data.length()) + "]: " + i_data);
Log->AddEvent(LogLevel_Verbose, "Save username BasicAuth[" + String(i_data.length()) + "]: " + i_data);
SaveString(EEPROM_ADDR_BASIC_AUTH_USERNAME_START, EEPROM_ADDR_BASIC_AUTH_USERNAME_LENGTH, i_data);
}
/**
@info save password fof BasicAuth to EEPROM
@param string - password
@ -669,7 +658,7 @@ void Configuration::SaveBasicAuthUsername(String i_data) {
*/
void Configuration::SaveBasicAuthPassword(String i_data) {
uint8_t len = i_data.length();
Log->AddEvent(LogLevel_Verbose, F("Save password BasicAuth["), String(len) + "]: ");
Log->AddEvent(LogLevel_Verbose, "Save password BasicAuth[" + String(len) + "]: ");
SaveString(EEPROM_ADDR_BASIC_AUTH_PASSWORD_START, EEPROM_ADDR_BASIC_AUTH_PASSWORD_LENGTH, i_data);
}
@ -679,7 +668,7 @@ void Configuration::SaveBasicAuthPassword(String i_data) {
@return none
*/
void Configuration::SaveBasicAuthFlag(bool i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save Enable/disable BasicAuth: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save Enable/disable BasicAuth: " + String(i_data));
SaveBool(EEPROM_ADDR_BASIC_AUTH_ENABLE_FLAG_START, i_data);
}
@ -689,7 +678,7 @@ void Configuration::SaveBasicAuthFlag(bool i_data) {
@return none
*/
void Configuration::SaveCameraFlashEnable(uint8_t i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save Enable/disable camera flash: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save Enable/disable camera flash: " + String(i_data));
SaveUint8(EEPROM_ADDR_CAMERA_FLASH_ENABLE_START, i_data);
}
@ -699,7 +688,7 @@ void Configuration::SaveCameraFlashEnable(uint8_t i_data) {
@return none
*/
void Configuration::SaveCameraFlashTime(uint16_t i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save camera flash time: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save camera flash time: " + String(i_data));
SaveUint16(EEPROM_ADDR_CAMERA_FLASH_TIME_START, i_data);
}
@ -709,7 +698,7 @@ void Configuration::SaveCameraFlashTime(uint16_t i_data) {
@return none
*/
void Configuration::SaveMdnsRecord(String i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save mDNS record["), String(i_data.length()) + "]: " + String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save mDNS record[" + String(i_data.length()) + "]: " + String(i_data));
SaveString(EEPROM_ADDR_MDNS_RECORD_START, EEPROM_ADDR_MDNS_RECORD_LENGTH, i_data);
}
@ -719,7 +708,7 @@ void Configuration::SaveMdnsRecord(String i_data) {
@return none
*/
void Configuration::SaveAec2(bool i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save Enable/disable AEC2: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save Enable/disable AEC2: " + String(i_data));
SaveBool(EEPROM_ADDR_AEC2_START, i_data);
}
@ -729,7 +718,7 @@ void Configuration::SaveAec2(bool i_data) {
@return none
*/
void Configuration::SaveAeLevel(int8_t i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save ae_level: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save ae_level: " + String(i_data));
SaveBool(EEPROM_ADDR_AE_LEVEL_START, i_data);
}
@ -739,7 +728,7 @@ void Configuration::SaveAeLevel(int8_t i_data) {
@return none
*/
void Configuration::SaveAecValue(uint16_t i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save aec value time: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save aec value time: " + String(i_data));
SaveUint16(EEPROM_ADDR_AEC_VALUE_START, i_data);
}
@ -749,7 +738,7 @@ void Configuration::SaveAecValue(uint16_t i_data) {
@return none
*/
void Configuration::SaveGainCtrl(bool i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save gain_ctrl: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save gain_ctrl: " + String(i_data));
SaveBool(EEPROM_ADDR_GAIN_CTRL_START, i_data);
}
@ -759,7 +748,7 @@ void Configuration::SaveGainCtrl(bool i_data) {
@return none
*/
void Configuration::SaveAgcGain(uint8_t i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save agc_gain: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save agc_gain: " + String(i_data));
SaveUint8(EEPROM_ADDR_AGC_GAIN_START, i_data);
}
@ -769,7 +758,7 @@ void Configuration::SaveAgcGain(uint8_t i_data) {
@return none
*/
void Configuration::SaveLogLevel(LogLevel_enum i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save log level: "), String(i_data));
Log->AddEvent(LogLevel_Verbose, "Save log level: " + String(i_data));
SaveUint8(EEPROM_ADDR_LOG_LEVEL, i_data);
}
@ -779,7 +768,7 @@ void Configuration::SaveLogLevel(LogLevel_enum i_data) {
* @return none
*/
void Configuration::SavePrusaConnectHostname(String i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save PrusaConnectHostanme["), String(i_data.length()) + "]: " + i_data);
Log->AddEvent(LogLevel_Verbose, "Save PrusaConnectHostanme[" + String(i_data.length()) + "]: " + i_data);
SaveString(EEPROM_ADDR_HOSTNAME_START, EEPROM_ADDR_HOSTNAME_LENGTH, i_data);
}
@ -799,7 +788,7 @@ void Configuration::SaveNetworkIpMethod(uint8_t i_data) {
@return none
*/
void Configuration::SaveNetworkIp(String i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save network static ip: "), i_data);
Log->AddEvent(LogLevel_Verbose, "Save network static ip: " + i_data);
SaveIpAddress(EEPROM_ADDR_NETWORK_STATIC_IP_START, i_data);
}
@ -810,7 +799,7 @@ void Configuration::SaveNetworkIp(String i_data) {
@return none
*/
void Configuration::SaveNetworkMask(String i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save network static mask: "), i_data);
Log->AddEvent(LogLevel_Verbose, "Save network static mask: " + i_data);
SaveIpAddress(EEPROM_ADDR_NETWORK_STATIC_MASK_START, i_data);
}
@ -820,7 +809,7 @@ void Configuration::SaveNetworkMask(String i_data) {
@return none
*/
void Configuration::SaveNetworkGateway(String i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save network static gateway: "), i_data);
Log->AddEvent(LogLevel_Verbose, "Save network static gateway: " + i_data);
SaveIpAddress(EEPROM_ADDR_NETWORK_STATIC_GATEWAY_START, i_data);
}
@ -830,50 +819,10 @@ void Configuration::SaveNetworkGateway(String i_data) {
@return none
*/
void Configuration::SaveNetworkDns(String i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save network static dns: "), i_data);
Log->AddEvent(LogLevel_Verbose, "Save network static dns: " + i_data);
SaveIpAddress(EEPROM_ADDR_NETWORK_STATIC_DNS_START, i_data);
}
/**
@info Save camera image rotation
@param uint8_t - value
@return none
*/
void Configuration::SaveCameraImageExifRotation(uint8_t i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save camera image exif rotation: "), String(i_data));
SaveUint8(EEPROM_ADDR_IMAGE_ROTATION_START, i_data);
}
/**
@info Save time lapse function status
@param bool - value
@return none
*/
void Configuration::SaveTimeLapseFunctionStatus(bool i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save time lapse function status: "), String(i_data));
SaveBool(EEPROM_ADDR_TIMELAPS_ENABLE_START, i_data);
}
/**
@info Save external temperature sensor enable
@param bool - value
@return none
*/
void Configuration::SaveExternalTemperatureSensorEnable(bool i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save external temperature sensor enable: "), String(i_data));
SaveBool(EEPROM_ADDR_EXT_SENS_ENABLE_START, i_data);
}
/**
@info Save external temperature sensor unit
@param uint8_t - value
@return none
*/
void Configuration::SaveExternalTemperatureSensorUnit(uint8_t i_data) {
Log->AddEvent(LogLevel_Verbose, F("Save external temperature sensor unit: "), String(i_data));
SaveUint8(EEPROM_ADDR_EXT_SENS_UNIT_START, i_data);
}
/**
@info load refresh interval from eeprom
@param none
@ -881,7 +830,7 @@ void Configuration::SaveExternalTemperatureSensorUnit(uint8_t i_data) {
*/
uint8_t Configuration::LoadRefreshInterval() {
uint8_t ret = EEPROM.read(EEPROM_ADDR_REFRESH_INTERVAL_START);
Log->AddEvent(LogLevel_Info, F("Refresh interval: "), String(ret));
Log->AddEvent(LogLevel_Info, "Refresh interval: " + String(ret));
return ret;
}
@ -892,7 +841,7 @@ uint8_t Configuration::LoadRefreshInterval() {
@return String - token
*/
String Configuration::LoadToken() {
Log->AddEvent(LogLevel_Info, F("Token: "), false);
Log->AddEvent(LogLevel_Info, "Token: ", false);
String ret = LoadString(EEPROM_ADDR_TOKEN_START, EEPROM_ADDR_TOKEN_LENGTH, CONSOLE_VERBOSE_DEBUG);
return ret;
@ -904,7 +853,7 @@ String Configuration::LoadToken() {
@return String - fingerprint
*/
String Configuration::LoadFingerprint() {
Log->AddEvent(LogLevel_Info, F("Fingerprint: "), false);
Log->AddEvent(LogLevel_Info, "Fingerprint: ", false);
String ret = LoadString(EEPROM_ADDR_FINGERPRINT_START, EEPROM_ADDR_FINGERPRINT_LENGTH, true);
return ret;
@ -917,7 +866,7 @@ String Configuration::LoadFingerprint() {
*/
uint8_t Configuration::LoadPhotoQuality() {
uint8_t ret = EEPROM.read(EEPROM_ADDR_PHOTO_QUALITY_START);
Log->AddEvent(LogLevel_Info, F("Photo quality: "), String(ret));
Log->AddEvent(LogLevel_Info, "Photo quality: " + String(ret));
return ret;
}
@ -929,7 +878,7 @@ uint8_t Configuration::LoadPhotoQuality() {
*/
uint8_t Configuration::LoadFrameSize() {
uint8_t ret = EEPROM.read(EEPROM_ADDR_FRAMESIZE_START);
Log->AddEvent(LogLevel_Info, F("Framesize: "), String(ret));
Log->AddEvent(LogLevel_Info, "Framesize: " + String(ret));
return ret;
}
@ -940,7 +889,7 @@ uint8_t Configuration::LoadFrameSize() {
*/
int8_t Configuration::LoadBrightness() {
int8_t ret = EEPROM.read(EEPROM_ADDR_BRIGHTNESS_START);
Log->AddEvent(LogLevel_Info, F("brightness: "), String(ret));
Log->AddEvent(LogLevel_Info, "brightness: " + String(ret));
return ret;
}
@ -952,7 +901,7 @@ int8_t Configuration::LoadBrightness() {
*/
int8_t Configuration::LoadContrast() {
int8_t ret = EEPROM.read(EEPROM_ADDR_CONTRAST_START);
Log->AddEvent(LogLevel_Info, F("contrast: "), String(ret));
Log->AddEvent(LogLevel_Info, "contrast: " + String(ret));
return ret;
}
@ -964,7 +913,7 @@ int8_t Configuration::LoadContrast() {
*/
int8_t Configuration::LoadSaturation() {
int8_t ret = EEPROM.read(EEPROM_ADDR_SATURATION_START);
Log->AddEvent(LogLevel_Info, F("saturation: "), String(ret));
Log->AddEvent(LogLevel_Info, "saturation: " + String(ret));
return ret;
}
@ -976,7 +925,7 @@ int8_t Configuration::LoadSaturation() {
*/
bool Configuration::LoadHmirror() {
bool ret = EEPROM.read(EEPROM_ADDR_HMIRROR_START);
Log->AddEvent(LogLevel_Info, F("hmirror: "), String(ret));
Log->AddEvent(LogLevel_Info, "hmirror: " + String(ret));
return ret;
}
@ -988,7 +937,7 @@ bool Configuration::LoadHmirror() {
*/
bool Configuration::LoadVflip() {
bool ret = EEPROM.read(EEPROM_ADDR_VFLIP_START);
Log->AddEvent(LogLevel_Info, F("vflip: "), String(ret));
Log->AddEvent(LogLevel_Info, "vflip: " + String(ret));
return ret;
}
@ -1000,7 +949,7 @@ bool Configuration::LoadVflip() {
*/
bool Configuration::LoadLensCorrect() {
bool ret = EEPROM.read(EEPROM_ADDR_LENSC_START);
Log->AddEvent(LogLevel_Info, F("lensc: "), String(ret));
Log->AddEvent(LogLevel_Info, "lensc: " + String(ret));
return ret;
}
@ -1012,7 +961,7 @@ bool Configuration::LoadLensCorrect() {
*/
bool Configuration::LoadExposureCtrl() {
bool ret = EEPROM.read(EEPROM_ADDR_EXPOSURE_CTRL_START);
Log->AddEvent(LogLevel_Info, F("exposure_ctrl: "), String(ret));
Log->AddEvent(LogLevel_Info, "exposure_ctrl: " + String(ret));
return ret;
}
@ -1024,7 +973,7 @@ bool Configuration::LoadExposureCtrl() {
*/
bool Configuration::LoadAwb() {
bool ret = EEPROM.read(EEPROM_ADDR_AWB_ENABLE_START);
Log->AddEvent(LogLevel_Info, F("awb: "), String(ret));
Log->AddEvent(LogLevel_Info, "awb: " + String(ret));
return ret;
}
@ -1036,7 +985,7 @@ bool Configuration::LoadAwb() {
*/
bool Configuration::LoadAwbGain() {
bool ret = EEPROM.read(EEPROM_ADDR_AWB_GAIN_ENABLE_START);
Log->AddEvent(LogLevel_Info, F("awb_gain: "), String(ret));
Log->AddEvent(LogLevel_Info, "awb_gain: " + String(ret));
return ret;
}
@ -1048,7 +997,7 @@ bool Configuration::LoadAwbGain() {
*/
uint8_t Configuration::LoadAwbMode() {
uint8_t ret = EEPROM.read(EEPROM_ADDR_AWB_MODE_ENABLE_START);
Log->AddEvent(LogLevel_Info, F("awb_mode: "), String(ret));
Log->AddEvent(LogLevel_Info, "awb_mode: " + String(ret));
return ret;
}
@ -1060,7 +1009,7 @@ uint8_t Configuration::LoadAwbMode() {
*/
bool Configuration::LoadBpc() {
bool ret = EEPROM.read(EEPROM_ADDR_BPC_ENABLE_START);
Log->AddEvent(LogLevel_Info, F("bpc: "), String(ret));
Log->AddEvent(LogLevel_Info, "bpc: " + String(ret));
return ret;
}
@ -1072,7 +1021,7 @@ bool Configuration::LoadBpc() {
*/
bool Configuration::LoadWpc() {
bool ret = EEPROM.read(EEPROM_ADDR_WPC_ENABLE_START);
Log->AddEvent(LogLevel_Info, F("wpc: "), String(ret));
Log->AddEvent(LogLevel_Info, "wpc: " + String(ret));
return ret;
}
@ -1084,7 +1033,7 @@ bool Configuration::LoadWpc() {
*/
bool Configuration::LoadRawGama() {
bool ret = EEPROM.read(EEPROM_ADDR_RAW_GAMA_ENABLE_START);
Log->AddEvent(LogLevel_Info, F("raw_gama: "), String(ret));
Log->AddEvent(LogLevel_Info, "raw_gama: " + String(ret));
return ret;
}
@ -1095,7 +1044,7 @@ bool Configuration::LoadRawGama() {
@return String - WI-FI SSID
*/
String Configuration::LoadWifiSsid() {
Log->AddEvent(LogLevel_Info, F("SSID: "), false);
Log->AddEvent(LogLevel_Info, "SSID: ", false);
String ret = LoadString(EEPROM_ADDR_WIFI_SSID_START, EEPROM_ADDR_WIFI_SSID_LENGTH, true);
return ret;
@ -1107,7 +1056,7 @@ String Configuration::LoadWifiSsid() {
@return String - WI-FI password
*/
String Configuration::LoadWifiPassowrd() {
Log->AddEvent(LogLevel_Info, F("WiFi password: "), false);
Log->AddEvent(LogLevel_Info, "WiFi password: ", false);
String ret = LoadString(EEPROM_ADDR_WIFI_PASSWORD_START, EEPROM_ADDR_WIFI_PASSWORD_LENGTH, CONSOLE_VERBOSE_DEBUG);
return ret;
@ -1125,7 +1074,7 @@ bool Configuration::LoadEnableServiceAp() {
if ((255 == tmp) || (1 == tmp)) {
ret = true;
}
Log->AddEvent(LogLevel_Info, F("Enable Service AP: "), String(ret));
Log->AddEvent(LogLevel_Info, "Enable Service AP: " + String(ret));
return ret;
}
@ -1136,7 +1085,7 @@ bool Configuration::LoadEnableServiceAp() {
@return String - username
*/
String Configuration::LoadBasicAuthUsername() {
Log->AddEvent(LogLevel_Info, F("web auth user: "), false);
Log->AddEvent(LogLevel_Info, "web auth user: ", false);
String ret = LoadString(EEPROM_ADDR_BASIC_AUTH_USERNAME_START, EEPROM_ADDR_BASIC_AUTH_USERNAME_LENGTH, true);
return ret;
@ -1148,7 +1097,7 @@ String Configuration::LoadBasicAuthUsername() {
@return String - password
*/
String Configuration::LoadBasicAuthPassword() {
Log->AddEvent(LogLevel_Info, F("web auth pass: "), false);
Log->AddEvent(LogLevel_Info, "web auth pass: ", false);
String ret = LoadString(EEPROM_ADDR_BASIC_AUTH_PASSWORD_START, EEPROM_ADDR_BASIC_AUTH_PASSWORD_LENGTH, CONSOLE_VERBOSE_DEBUG);
return ret;
@ -1161,7 +1110,7 @@ String Configuration::LoadBasicAuthPassword() {
*/
bool Configuration::LoadBasicAuthFlag() {
bool ret = EEPROM.read(EEPROM_ADDR_BASIC_AUTH_ENABLE_FLAG_START);
Log->AddEvent(LogLevel_Info, F("web auth enable: "), String(ret));
Log->AddEvent(LogLevel_Info, "web auth enable: " + String(ret));
return ret;
}
@ -1173,7 +1122,7 @@ bool Configuration::LoadBasicAuthFlag() {
*/
bool Configuration::LoadCameraFlashEnable() {
bool ret = EEPROM.read(EEPROM_ADDR_CAMERA_FLASH_ENABLE_START);
Log->AddEvent(LogLevel_Info, F("Camera flash: "), String(ret));
Log->AddEvent(LogLevel_Info, "Camera flash: " + String(ret));
return ret;
}
@ -1185,7 +1134,7 @@ bool Configuration::LoadCameraFlashEnable() {
*/
uint16_t Configuration::LoadCameraFlashTime() {
uint16_t ret = LoadUint16(EEPROM_ADDR_CAMERA_FLASH_TIME_START);
Log->AddEvent(LogLevel_Info, F("Camera flash time: "), String(ret));
Log->AddEvent(LogLevel_Info, "Camera flash time: " + String(ret));
return ret;
}
@ -1196,7 +1145,7 @@ uint16_t Configuration::LoadCameraFlashTime() {
@return String - mDNS record
*/
String Configuration::LoadMdnsRecord() {
Log->AddEvent(LogLevel_Info, F("mDNS: "), false);
Log->AddEvent(LogLevel_Info, "mDNS: ", false);
String ret = LoadString(EEPROM_ADDR_MDNS_RECORD_START, EEPROM_ADDR_MDNS_RECORD_LENGTH, true);
return ret;
@ -1209,7 +1158,7 @@ String Configuration::LoadMdnsRecord() {
*/
bool Configuration::LoadAec2() {
bool ret = EEPROM.read(EEPROM_ADDR_AEC2_START);
Log->AddEvent(LogLevel_Info, F("aec2: "), String(ret));
Log->AddEvent(LogLevel_Info, "aec2: " + String(ret));
return ret;
}
@ -1221,7 +1170,7 @@ bool Configuration::LoadAec2() {
*/
int8_t Configuration::LoadAeLevel() {
int8_t ret = EEPROM.read(EEPROM_ADDR_AE_LEVEL_START);
Log->AddEvent(LogLevel_Info, F("ae_level: "), String(ret));
Log->AddEvent(LogLevel_Info, "ae_level: " + String(ret));
return ret;
}
@ -1233,7 +1182,7 @@ int8_t Configuration::LoadAeLevel() {
*/
uint16_t Configuration::LoadAecValue() {
uint16_t ret = LoadUint16(EEPROM_ADDR_AEC_VALUE_START);
Log->AddEvent(LogLevel_Info, F("aec_value: "), String(ret));
Log->AddEvent(LogLevel_Info, "aec_value: " + String(ret));
return ret;
}
@ -1245,7 +1194,7 @@ uint16_t Configuration::LoadAecValue() {
*/
bool Configuration::LoadGainCtrl() {
bool ret = EEPROM.read(EEPROM_ADDR_GAIN_CTRL_START);
Log->AddEvent(LogLevel_Info, F("gain_ctrl: "), String(ret));
Log->AddEvent(LogLevel_Info, "gain_ctrl: " + String(ret));
return ret;
}
@ -1257,7 +1206,7 @@ bool Configuration::LoadGainCtrl() {
*/
uint8_t Configuration::LoadAgcGain() {
uint8_t ret = EEPROM.read(EEPROM_ADDR_AGC_GAIN_START);
Log->AddEvent(LogLevel_Info, F("agc_gain: "), String(ret));
Log->AddEvent(LogLevel_Info, "agc_gain: " + String(ret));
return ret;
}
@ -1269,7 +1218,7 @@ uint8_t Configuration::LoadAgcGain() {
*/
LogLevel_enum Configuration::LoadLogLevel() {
LogLevel_enum ret = (LogLevel_enum) EEPROM.read(EEPROM_ADDR_LOG_LEVEL);
Log->AddEvent(LogLevel_Info, F("LogLevel: "), String(ret));
Log->AddEvent(LogLevel_Info, "LogLevel: " + String(ret));
return ret;
}
@ -1280,7 +1229,7 @@ LogLevel_enum Configuration::LoadLogLevel() {
* @return String - hostname
*/
String Configuration::LoadPrusaConnectHostname() {
Log->AddEvent(LogLevel_Info, F("PrusaConnect hostname: "), false);
Log->AddEvent(LogLevel_Info, "PrusaConnect hostname: ", false);
String ret = LoadString(EEPROM_ADDR_HOSTNAME_START, EEPROM_ADDR_HOSTNAME_LENGTH, true);
return ret;
@ -1310,7 +1259,7 @@ uint8_t Configuration::LoadNetworkIpMethod() {
*/
String Configuration::LoadNetworkIp() {
String ret = LoadIpAddress(EEPROM_ADDR_NETWORK_STATIC_IP_START);
Log->AddEvent(LogLevel_Info, F("Network static IP: "), ret);
Log->AddEvent(LogLevel_Info, "Network static IP: " + ret);
return ret;
}
@ -1322,7 +1271,7 @@ String Configuration::LoadNetworkIp() {
*/
String Configuration::LoadNetworkMask() {
String ret = LoadIpAddress(EEPROM_ADDR_NETWORK_STATIC_MASK_START);
Log->AddEvent(LogLevel_Info, F("Network static mask: "), ret);
Log->AddEvent(LogLevel_Info, "Network static mask: " + ret);
return ret;
}
@ -1334,7 +1283,7 @@ String Configuration::LoadNetworkMask() {
*/
String Configuration::LoadNetworkGateway() {
String ret = LoadIpAddress(EEPROM_ADDR_NETWORK_STATIC_GATEWAY_START);
Log->AddEvent(LogLevel_Info, F("Network static gateway: "), ret);
Log->AddEvent(LogLevel_Info, "Network static gateway: " + ret);
return ret;
}
@ -1346,76 +1295,9 @@ String Configuration::LoadNetworkGateway() {
*/
String Configuration::LoadNetworkDns() {
String ret = LoadIpAddress(EEPROM_ADDR_NETWORK_STATIC_DNS_START);
Log->AddEvent(LogLevel_Info, F("Network static DNS: "), ret);
Log->AddEvent(LogLevel_Info, "Network static DNS: " + ret);
return ret;
}
/**
* @brief Load camera image rotation from EEPROM
*
* @return uint8_t - rotation
*/
uint8_t Configuration::LoadCameraImageExifRotation() {
uint8_t ret = EEPROM.read(EEPROM_ADDR_IMAGE_ROTATION_START);
/* check if value is 255. When value is 255, then set default value */
if (ret == 255) {
ret = 1;
}
Log->AddEvent(LogLevel_Info, F("Camera image rotation: "), String(ret));
return ret;
}
/**
* @brief Load time lapse function status
*
* @return bool - status
*/
bool Configuration::LoadTimeLapseFunctionStatus() {
uint8_t ret = EEPROM.read(EEPROM_ADDR_TIMELAPS_ENABLE_START);
Log->AddEvent(LogLevel_Info, F("Time lapse function status: "), String(ret));
if (ret == 255) {
ret = 0;
}
return (bool) ret;
}
/**
* @brief Load external temperature sensor enable
*
* @return bool - status
*/
bool Configuration::LoadExternalTemperatureSensorEnable() {
uint8_t ret = EEPROM.read(EEPROM_ADDR_EXT_SENS_ENABLE_START);
Log->AddEvent(LogLevel_Info, F("External temperature sensor enable: "), String(ret));
if (ret == 255) {
ret = 0;
}
return (bool) ret;
}
/**
* @brief Load external temperature sensor unit
*
* @return uint8_t - unit
*/
uint8_t Configuration::LoadExternalTemperatureSensorUnit() {
uint8_t ret = EEPROM.read(EEPROM_ADDR_EXT_SENS_UNIT_START);
Log->AddEvent(LogLevel_Info, F("External temperature sensor unit: "), String(ret));
if (ret == 255) {
ret = 0;
}
return ret;
}
/* EOF */

View File

@ -9,24 +9,23 @@
@bug: no know bug
*/
#pragma once
#ifndef _CFG_H_
#define _CFG_H_
#include <WiFi.h>
#include <EEPROM.h>
#include <Arduino.h>
#include "Arduino.h"
#include <ArduinoUniqueID.h>
#include <base64.h>
#include "micro_sd.h"
#include "log.h"
#include "log_level.h"
#include "mcu_cfg.h"
#include "module_templates.h"
#include "Camera_cfg.h"
#include "var.h"
#include "wifi_mngt.h"
#include "log.h"
class Configuration {
public:
Configuration(Logs *);
Configuration(Logs*);
~Configuration(){};
void Init();
bool CheckActifeWifiCfgFlag();
@ -72,10 +71,6 @@ public:
void SaveNetworkMask(String);
void SaveNetworkGateway(String);
void SaveNetworkDns(String);
void SaveCameraImageExifRotation(uint8_t);
void SaveTimeLapseFunctionStatus(bool);
void SaveExternalTemperatureSensorEnable(bool);
void SaveExternalTemperatureSensorUnit(uint8_t);
uint8_t LoadRefreshInterval();
String LoadToken();
@ -116,10 +111,6 @@ public:
String LoadNetworkMask();
String LoadNetworkGateway();
String LoadNetworkDns();
uint8_t LoadCameraImageExifRotation();
bool LoadTimeLapseFunctionStatus();
bool LoadExternalTemperatureSensorEnable();
uint8_t LoadExternalTemperatureSensorUnit();
private:
Logs *Log; ///< Pointer to Logs object
@ -144,4 +135,6 @@ private:
extern Configuration SystemConfig; ///< Configuration object
#endif
/* EOF */

View File

@ -11,7 +11,7 @@
#include "connect.h"
PrusaConnect Connect(&SystemConfig, &SystemLog, &SystemCamera, &SystemWifiMngt);
PrusaConnect Connect(&SystemConfig, &SystemLog, &SystemCamera);
/**
* @brief Constructor for PrusaConnect class
@ -20,11 +20,10 @@ PrusaConnect Connect(&SystemConfig, &SystemLog, &SystemCamera, &SystemWifiMngt);
* @param Logs* - pointer to Logs class
* @param Camera* - pointer to Camera class
*/
PrusaConnect::PrusaConnect(Configuration *i_conf, Logs *i_log, Camera *i_camera, WiFiMngt *i_wifi) {
PrusaConnect::PrusaConnect(Configuration *i_conf, Logs *i_log, Camera *i_camera) {
config = i_conf;
log = i_log;
camera = i_camera;
wifi = i_wifi;
BackendAvailability = WaitForFirstConnection;
SendDeviceInformationToBackend = true;
}
@ -37,7 +36,7 @@ PrusaConnect::PrusaConnect(Configuration *i_conf, Logs *i_log, Camera *i_camera,
*/
void PrusaConnect::Init() {
log->AddEvent(LogLevel_Info, F("Init PrusaConnect lib"));
BackendReceivedStatus = F("Wait for first connection");
TakePicture();
}
/**
@ -52,7 +51,6 @@ void PrusaConnect::LoadCfgFromEeprom() {
Fingerprint = config->LoadFingerprint();
RefreshInterval = config->LoadRefreshInterval();
PrusaConnectHostname = config->LoadPrusaConnectHostname();
EnableTimelapsPhotoSave = config->LoadTimeLapseFunctionStatus();
}
/**
@ -85,10 +83,7 @@ bool PrusaConnect::SendDataToBackend(String *i_data, int i_data_length, String i
/* check fingerprint and token length */
if ((Fingerprint.length() > 0) && (Token.length() > 0)) {
client.setCACert(root_CAs);
//client.setInsecure();
client.setTimeout(1000);
client.setNoDelay(true);
log->AddEvent(LogLevel_Verbose, F("Connecting to server..."));
/* connecting to server */
@ -107,7 +102,7 @@ bool PrusaConnect::SendDataToBackend(String *i_data, int i_data_length, String i
} else {
/* send data to server */
log->AddEvent(LogLevel_Verbose, F("Connected to server!"));
client.println("PUT https://" + PrusaConnectHostname + i_url_path + " HTTP/1.1");
client.println("PUT https://" + PrusaConnectHostname + i_url_path + " HTTP/1.0");
client.println("Host: " + PrusaConnectHostname);
client.println("User-Agent: ESP32-CAM");
client.println("Connection: close");
@ -119,78 +114,38 @@ bool PrusaConnect::SendDataToBackend(String *i_data, int i_data_length, String i
client.println();
esp_task_wdt_reset();
size_t sendet_data = 0;
/* sending photo */
if (SendPhoto == i_data_type) {
log->AddEvent(LogLevel_Verbose, F("Sendig photo"));
/* get photo buffer */
bool SendWithExif = false;
uint8_t *fbBuf = NULL;
size_t fbLen = 0;
if (camera->GetStreamStatus() == true) {
/* get duplicate photo buffer from camera */
fbBuf = camera->GetPhotoFbDuplicate()->buf;
fbLen = camera->GetPhotoFbDuplicate()->len;
} else {
/* get original photo buffer from camera */
fbBuf = camera->GetPhotoFb()->buf;
fbLen = camera->GetPhotoFb()->len;
log->AddEvent(LogLevel_Verbose, F("Send data photo"));
int index = 0;
/* send data in fragments */
for (index = 0; index < i_data_length; index += PHOTO_FRAGMENT_SIZE) {
camera->CopyPhoto(i_data, index, index + PHOTO_FRAGMENT_SIZE);
client.print(*i_data);
log->AddEvent(LogLevel_Verbose, String(i_data_length) + "/" + String(index));
}
/* sending exif data */
if ((camera->GetPhotoExifData()->header != NULL) && (camera->GetStreamStatus() == false)) {
SendWithExif = true;
sendet_data += client.write(camera->GetPhotoExifData()->header, camera->GetPhotoExifData()->len);
fbBuf += camera->GetPhotoExifData()->offset;
fbLen -= camera->GetPhotoExifData()->offset;
} else {
SendWithExif = false;
/* send rest of data */
index -= PHOTO_FRAGMENT_SIZE;
if ((i_data_length > index) && ((i_data_length - index) > 0)) {
camera->CopyPhoto(i_data, index, i_data_length);
client.print(*i_data);
log->AddEvent(LogLevel_Verbose, String(i_data_length) + "/" + String(i_data_length));
}
/* sending photo */
for (size_t i = 0; i < fbLen; i += PHOTO_FRAGMENT_SIZE) {
if ((i + PHOTO_FRAGMENT_SIZE) < fbLen) {
sendet_data += client.write(fbBuf, PHOTO_FRAGMENT_SIZE);
fbBuf += PHOTO_FRAGMENT_SIZE;
} else if ((fbLen % PHOTO_FRAGMENT_SIZE) > 0) {
size_t remainder = fbLen % PHOTO_FRAGMENT_SIZE;
sendet_data += client.write(fbBuf, remainder);
}
}
client.println("\r\n");
/* log message */
if (SendWithExif) {
SystemLog.AddEvent(LogLevel_Verbose, F("Photo with EXIF data sent"));
} else {
SystemLog.AddEvent(LogLevel_Warning, F("Photo without EXIF data sent"));
}
/* sending device information */
/* sending device information */
} else if (SendInfo == i_data_type) {
log->AddEvent(LogLevel_Verbose, F("Sending info"));
sendet_data = client.print(*i_data);
log->AddEvent(LogLevel_Verbose, F("Send data info"));
client.print(*i_data);
}
client.flush();
log->AddEvent(LogLevel_Info, "Send done: " + String(i_data_length) + "/" + String(sendet_data) + " bytes");
/* check if all data was sent */
if (i_data_length != sendet_data) {
BackendReceivedStatus = F("INCOMPLETE DATA SEND TO SERVER!");
log->AddEvent(LogLevel_Error, F("ERROR SEND DATA TO SERVER! INCORRECT DATA LENGTH!"));
client.stop();
return false;
}
//esp_task_wdt_reset();
log->AddEvent(LogLevel_Info, "Send done: " + String(i_data_length) + " bytes");
esp_task_wdt_reset();
/* read response from server */
String response = "";
String fullResponse = "";
delay(10); // wait for response
log->AddEvent(LogLevel_Verbose, F("Response:"));
log->AddEvent(LogLevel_Verbose, "Response:");
while (client.connected()) {
if (client.available()) {
response = client.readStringUntil('\n');
@ -238,19 +193,9 @@ bool PrusaConnect::SendDataToBackend(String *i_data, int i_data_length, String i
*/
void PrusaConnect::SendPhotoToBackend() {
log->AddEvent(LogLevel_Info, F("Start sending photo to prusaconnect"));
camera->SetPhotoSending(true);
String Photo = "";
size_t total_len = 0;
if ((camera->GetPhotoExifData()->header != NULL) && (camera->GetStreamStatus() == false)) {
total_len = camera->GetPhotoExifData()->len + camera->GetPhotoFb()->len - camera->GetPhotoExifData()->offset;
} else if (camera->GetStreamStatus() == false) {
total_len = camera->GetPhotoFb()->len;
} else {
total_len = camera->GetPhotoFbDuplicate()->len;
}
SendDataToBackend(&Photo, total_len, F("image/jpg"), F("Photo"), HOST_URL_CAM_PATH, SendPhoto);
camera->SetPhotoSending(false);
SendDataToBackend(&Photo, camera->GetPhotoSize(), "image/jpg", "Photo", HOST_URL_CAM_PATH, SendPhoto);
SystemLog.AddEvent(LogLevel_Info, "Free RAM: " + String(ESP.getFreeHeap()) + " bytes");
}
/**
@ -268,10 +213,7 @@ void PrusaConnect::SendInfoToBackend() {
String json_string = "";
JsonObject config = json_data["config"].to<JsonObject>();
config["name"] = wifi->GetMdns();
config["firmware"] = SW_VERSION;
config["manufacturer"] = F("Prusa");
config["model"] = BOARD_NAME;
config["name"] = "ESP32-CAM";
JsonObject resolution = config["resolution"].to<JsonObject>();
resolution["width"] = SystemCamera.GetFrameSizeWidth();
@ -284,7 +226,7 @@ void PrusaConnect::SendInfoToBackend() {
serializeJson(json_data, json_string);
log->AddEvent(LogLevel_Info, "Data: " + json_string);
bool response = SendDataToBackend(&json_string, json_string.length(), F("application/json"), F("Info"), HOST_URL_INFO_PATH, SendInfo);
bool response = SendDataToBackend(&json_string, json_string.length(), "application/json", "Info", HOST_URL_INFO_PATH, SendInfo);
if (true == response) {
SendDeviceInformationToBackend = false;
@ -299,28 +241,8 @@ void PrusaConnect::SendInfoToBackend() {
* @return none
*/
void PrusaConnect::TakePictureAndSendToBackend() {
camera->CapturePhoto();
/* check if photo was captured */
if (camera->GetCameraCaptureSuccess() == true) {
/* send photo to backend */
SendPhotoToBackend();
/* save photo to SD card */
if (false == camera->GetStreamStatus()) {
SavePhotoToSdCard();
}
} else {
log->AddEvent(LogLevel_Error, F("Error capturing photo. Stop sending to backend!"));
}
/* return frame buffer */
if (camera->GetStreamStatus() == true) {
/* set stream flag for sending photo to false */
camera->StreamSetSendingPhoto(false);
}
TakePicture();
SendPhotoToBackend();
}
/**
@ -469,64 +391,6 @@ void PrusaConnect::SetPrusaConnectHostname(String i_data) {
config->SavePrusaConnectHostname(PrusaConnectHostname);
}
/**
* @brief Set time laps photo save status
*
* @param bool - status
*/
void PrusaConnect::SetTimeLapsPhotoSaveStatus(bool i_data) {
EnableTimelapsPhotoSave = i_data;
config->SaveTimeLapseFunctionStatus(EnableTimelapsPhotoSave);
}
/**
@brief Function for saving photo to SD card
@param none
@return none
*/
void PrusaConnect::SavePhotoToSdCard() {
#if (ENABLE_SD_CARD == true)
/* check if time laps photo save is enabled */
if (EnableTimelapsPhotoSave == true) {
log->AddEvent(LogLevel_Info, F("Save TimeLaps photo to SD card"));
/* check if SD card is detected */
if (log->GetCardDetectedStatus() == false) {
log->AddEvent(LogLevel_Error, F("SD card not detected!"));
return;
}
/* check if folder for time laps photos exists */
if (false == log->CheckDir(SD_MMC, TIMELAPS_PHOTO_FOLDER)) {
log->AddEvent(LogLevel_Info, F("Create folder for TimeLaps photos"));
log->CreateDir(SD_MMC, TIMELAPS_PHOTO_FOLDER);
}
/* create file name */
String FileName = String(TIMELAPS_PHOTO_FOLDER) + "/" + String(TIMELAPS_PHOTO_PREFIX) + "_";
FileName += log->GetSystemTime();
FileName += TIMELAPS_PHOTO_SUFFIX;
log->AddEvent(LogLevel_Verbose, F("Saving file: "), FileName);
/* save photo to SD card */
if (camera->GetPhotoExifData()->header != NULL) {
if (log->WritePicture(FileName, camera->GetPhotoFb()->buf + camera->GetPhotoExifData()->offset, camera->GetPhotoFb()->len - camera->GetPhotoExifData()->offset, camera->GetPhotoExifData()->header, camera->GetPhotoExifData()->len) == true) {
log->AddEvent(LogLevel_Info, F("Photo saved to SD card. EXIF"));
} else {
log->AddEvent(LogLevel_Error, F("Error saving photo to SD card. EXIF"));
}
} else {
if (log->WritePicture(FileName, camera->GetPhotoFb()->buf, camera->GetPhotoFb()->len) == true) {
log->AddEvent(LogLevel_Info, F("Photo saved to SD card"));
} else {
log->AddEvent(LogLevel_Error, F("Error saving photo to SD card"));
}
}
}
#endif
}
/**
* @brief Get refresh interval
*
@ -611,10 +475,6 @@ String PrusaConnect::CovertBackendAvailabilitStatusToString(BackendAvailabilitSt
return ret;
}
bool PrusaConnect::GetTimeLapsPhotoSaveStatus() {
return EnableTimelapsPhotoSave;
}
/**
* @brief Increase sending interval counter
*

View File

@ -8,12 +8,14 @@
@bug: no know bug
*/
#pragma once
#ifndef _PRUSA_CONNECT_H_
#define _PRUSA_CONNECT_H_
#include <WiFiClientSecure.h>
#include <HTTPClient.h>
#include <esp_task_wdt.h>
#include <Arduino.h>
#include "Arduino.h"
#include <ArduinoJson.h>
#include "wifi_mngt.h"
@ -23,12 +25,26 @@
#include "camera.h"
#include "cfg.h"
#include "Certificate.h"
#include "WebServer.h"
#include "connect_types.h"
#include "server.h"
class WiFiMngt;
class Configuration;
class Camera;
/**
* @brief BackendAvailabilitStatus enum
* status of backend availability
*/
enum BackendAvailabilitStatus {
WaitForFirstConnection = 0, ///< waiting for first connection to backend
BackendAvailable = 1, ///< backend is available
BackendUnavailable = 2, ///< backend is unavailable
};
/**
* @brief SendDataToBackendType enum
* type of data to send to backend
*/
enum SendDataToBackendType {
SendPhoto = 0, ///< send photo to backend
SendInfo = 1, ///< send device information to backend
};
class PrusaConnect {
private:
@ -37,7 +53,6 @@ private:
BackendAvailabilitStatus BackendAvailability; ///< status of backend availability
bool SendDeviceInformationToBackend; ///< flag for sending device information to backend
uint8_t SendingIntervalCounter; ///< counter for sending interval, represents seconds
bool EnableTimelapsPhotoSave; ///< flag for saving photo to SD card
String Token; ///< token for backend communication
String Fingerprint; ///< fingerprint for backend communication
@ -46,12 +61,11 @@ private:
Configuration *config; ///< pointer to configuration object
Logs *log; ///< pointer to logs object
Camera *camera; ///< pointer to camera object
WiFiMngt *wifi; ///< pointer to wifi object
bool SendDataToBackend(String *, int, String, String, String, SendDataToBackendType);
public:
PrusaConnect(Configuration*, Logs*, Camera*, WiFiMngt*);
PrusaConnect(Configuration*, Logs*, Camera*);
~PrusaConnect(){};
void Init();
@ -69,9 +83,6 @@ public:
void SetToken(String);
void SetBackendAvailabilitStatus(BackendAvailabilitStatus);
void SetPrusaConnectHostname(String);
void SetTimeLapsPhotoSaveStatus(bool);
void SavePhotoToSdCard();
uint8_t GetRefreshInterval();
String GetBackendReceivedStatus();
@ -80,7 +91,6 @@ public:
String GetPrusaConnectHostname();
BackendAvailabilitStatus GetBackendAvailabilitStatus();
String CovertBackendAvailabilitStatusToString(BackendAvailabilitStatus);
bool GetTimeLapsPhotoSaveStatus();
void IncreaseSendingIntervalCounter();
void SetSendingIntervalCounter(uint8_t);
@ -91,4 +101,4 @@ public:
extern PrusaConnect Connect; ///< PrusaConnect object
/* EOF */
#endif

View File

@ -1,31 +0,0 @@
/**
@file connect_types.h
@brief Here are defined types for communication with prusa connect backend
@author Miroslav Pivovarsky
Contact: miroslav.pivovarsky@gmail.com
@bug: no know bug
*/
#pragma once
/**
* @brief BackendAvailabilitStatus enum
* status of backend availability
*/
enum BackendAvailabilitStatus {
WaitForFirstConnection = 0, ///< waiting for first connection to backend
BackendAvailable = 1, ///< backend is available
BackendUnavailable = 2, ///< backend is unavailable
};
/**
* @brief SendDataToBackendType enum
* type of data to send to backend
*/
enum SendDataToBackendType {
SendPhoto = 0, ///< send photo to backend
SendInfo = 1, ///< send device information to backend
};

View File

@ -1,450 +0,0 @@
/**
* exif.c - Functions to generate Exif metadata
*
* Copyright (c) 2019, David Imhoff <dimhoff.devel@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the author nor the names of its contributors may
* be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO
* EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
* OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
* OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
* ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include <time.h>
#include <sys/time.h>
#include "exif.h"
#include "exif_defines.h"
// TIFF header byte order
#if __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
# define TIFF_BYTE_ORDER 0x4949
#else // __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
# define TIFF_BYTE_ORDER 0x4d4d
#endif // __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
// Reimplementation of htons() that can be used to initialize a struct member.
#if __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
# define htons_macro(x) \
(((x) & 0x00ff) << 8 | \
((x) & 0xff00) >> 8)
#else // __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
# define htons_macro(x) (x)
#endif // __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
/**
* Type for storing Tiff Rational typed data
*/
#pragma pack(1)
typedef struct {
uint32_t num;
uint32_t denom;
} TiffRational;
#pragma pack()
/**
* Type used for IFD entries
*
* This type is used to store a value within the Tiff IFD.
*/
#pragma pack(1)
typedef struct {
uint16_t tag; // Data tag
uint16_t type; // Data type
uint32_t length; // length of data
// Offset of data from start of TIFF data, or data it self if length <= 4.
// Always use the IFD_SET_*() macros to modify the value.
uint32_t value;
} IfdEntry;
#pragma pack()
// Some helper macros to initialize the IFD value's. The types shorter then
// 4-bytes need to be aligned such that they are directly after the previous
// field. These macros take care of this.
#if __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
# define IFD_SET_BYTE(VAL) (VAL)
# define IFD_SET_SHORT(VAL) (VAL)
# define IFD_SET_LONG(VAL) (VAL)
# define IFD_SET_OFFSET(REF, VAR) offsetof(REF, VAR)
# define IFD_SET_UNDEF(V0, V1, V2, V3) \
(((V3) & 0xff) << 24 | \
((V2) & 0xff) << 16 | \
((V1) & 0xff) << 8 | \
((V0) & 0xff))
#else // __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
# define IFD_SET_BYTE(VAL) (((VAL) & 0xff) << 24)
# define IFD_SET_SHORT(VAL) (((VAL) & 0xffff) << 16)
# define IFD_SET_LONG(VAL) (VAL)
# define IFD_SET_OFFSET(REF, VAR) offsetof(REF, VAR)
# define IFD_SET_UNDEF(V0, V1, V2, V3) \
(((V0) & 0xff) << 24 | \
((V1) & 0xff) << 16 | \
((V2) & 0xff) << 8 | \
((V3) & 0xff))
#endif // __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
// Amount of entries in the 0th IFD
#ifdef WITH_GNSS
# define IFD0_ENTRY_CNT 11
#else
# define IFD0_ENTRY_CNT 12
#endif
// Amount of entries in the Exif private IFD
#define IFD_EXIF_ENTRY_CNT 6
// Amount of entries in the GPS private IFD
#define IFD_GPS_ENTRY_CNT 12
// GPS map datum, probably always 'WGS-84'
#define GPS_MAP_DATUM "WGS-84"
/**
* New Jpeg/Exif header
*
* This defines the new JPEG/Exif header that is added to the images. To keep
* it simple, the structure of the header is completely static.
*/
#pragma pack(1)
struct JpegExifHdr {
uint16_t jpeg_soi; // htons(0xffd8)
uint16_t marker; // htons(0xffe1)
uint16_t len; // htons(length)
uint8_t exif_identifier[6]; // 'Exif\0\0'
struct TiffData {
struct {
uint16_t byte_order; // 'II' || 'MM'
uint16_t signature; // 0x002A
uint32_t ifd_offset; // 0x8
} tiff_hdr;
struct {
uint16_t cnt; // amount of entries
IfdEntry entries[IFD0_ENTRY_CNT];
uint32_t next_ifd; // Offset of next IFD, or 0x0 if last IFD
} ifd0;
struct {
TiffRational XYResolution;
char make[sizeof(CAMERA_MAKE)];
char model[sizeof(CAMERA_MODEL)];
char software[sizeof(CAMERA_SOFTWARE)];
char datetime[20];
} ifd0_data;
struct {
uint16_t cnt; // amount of entries
IfdEntry entries[IFD_EXIF_ENTRY_CNT];
uint32_t next_ifd; // Offset of next IFD, or 0x0 if last IFD
} ifd_exif;
#ifdef WITH_GNSS
struct {
uint16_t cnt; // amount of entries
IfdEntry entries[IFD_GPS_ENTRY_CNT];
uint32_t next_ifd; // Offset of next IFD, or 0x0 if last IFD
} ifd_gps;
struct {
TiffRational latitude[3];
TiffRational longitude[3];
TiffRational altitude;
TiffRational time_stamp[3];
char map_datum[sizeof(GPS_MAP_DATUM)];
uint8_t processing_method[8 + 3];
char date_stamp[11];
} ifd_gps_data;
#endif //WITH_GNSS
} tiff_data;
} exif_hdr = {
htons_macro(0xffd8),
htons_macro(0xffe1),
htons_macro(sizeof(JpegExifHdr) - offsetof(JpegExifHdr, len)),
{ 'E', 'x', 'i', 'f', 0, 0 },
{
.tiff_hdr = { TIFF_BYTE_ORDER, 0x002A, 0x8 },
.ifd0 = {
.cnt = IFD0_ENTRY_CNT,
.entries = {
{ TagTiffMake,
TiffTypeAscii,
sizeof(exif_hdr.tiff_data.ifd0_data.make),
IFD_SET_OFFSET(JpegExifHdr::TiffData, ifd0_data.make) },
{ TagTiffModel,
TiffTypeAscii,
sizeof(exif_hdr.tiff_data.ifd0_data.model),
IFD_SET_OFFSET(JpegExifHdr::TiffData, ifd0_data.model) },
#define TAG_IFD0_ORIENTATION_IDX 2
{ TagTiffOrientation,
TiffTypeShort, 1,
IFD_SET_SHORT(1) },
{ TagTiffXResolution,
TiffTypeRational, 1,
IFD_SET_OFFSET(JpegExifHdr::TiffData, ifd0_data) },
{ TagTiffYResolution,
TiffTypeRational, 1,
IFD_SET_OFFSET(JpegExifHdr::TiffData, ifd0_data) },
{ TagTiffResolutionUnit,
TiffTypeShort, 1,
IFD_SET_SHORT(0x0002) },
{ TagTiffSoftware,
TiffTypeAscii,
sizeof(exif_hdr.tiff_data.ifd0_data.software),
IFD_SET_OFFSET(JpegExifHdr::TiffData, ifd0_data.software) },
{ TagTiffDateTime,
TiffTypeAscii,
sizeof(exif_hdr.tiff_data.ifd0_data.datetime),
IFD_SET_OFFSET(JpegExifHdr::TiffData, ifd0_data.datetime) },
{ TagTiffYCbCrPositioning,
TiffTypeShort, 1,
IFD_SET_SHORT(0x0001) },
{ TagTiffExifIFD,
TiffTypeLong, 1,
IFD_SET_OFFSET(JpegExifHdr::TiffData, ifd_exif) },
#ifdef WITH_GNSS
{ TagTiffGPSIFD,
TiffTypeLong, 1,
IFD_SET_OFFSET(JpegExifHdr::TiffData, ifd_gps) },
#endif // WITH_GNSS
},
.next_ifd = 0
},
.ifd0_data = {
{ 72, 1 },
CAMERA_MAKE,
CAMERA_MODEL,
CAMERA_SOFTWARE,
" : : : : ",
},
.ifd_exif = {
.cnt = IFD_EXIF_ENTRY_CNT,
.entries = {
{ TagExifVersion,
TiffTypeUndef, 4,
IFD_SET_UNDEF(0x30, 0x32, 0x33, 0x30) },
{ TagExifComponentsConfiguration,
TiffTypeUndef, 4,
IFD_SET_UNDEF(0x01, 0x02, 0x03, 0x00) },
#define TAG_EXIF_SUBSEC_TIME_IDX 2
{ TagExifSubSecTime,
TiffTypeAscii, 4,
IFD_SET_UNDEF(0x20, 0x20, 0x20, 0x00) },
{ TagExifColorSpace,
TiffTypeShort, 1,
IFD_SET_SHORT(1) },
#define TAG_EXIF_PIXEL_X_DIMENSION_IDX 4
{ TagExifPixelXDimension,
TiffTypeShort, 1,
IFD_SET_SHORT(1600) },
#define TAG_EXIF_PIXEL_Y_DIMENSION_IDX (TAG_EXIF_PIXEL_X_DIMENSION_IDX + 1)
{ TagExifPixelYDimension,
TiffTypeShort, 1,
IFD_SET_SHORT(1200) },
},
.next_ifd = 0
},
#ifdef WITH_GNSS
.ifd_gps = {
.cnt = IFD_GPS_ENTRY_CNT,
.entries = {
{ TagGPSVersionID,
TiffTypeByte, 4,
IFD_SET_UNDEF(2, 3, 0, 0) },
#define TAG_GPS_LATITUDE_REF_IDX 1
{ TagGPSLatitudeRef,
TiffTypeAscii, 2,
IFD_SET_UNDEF(0x00, 0x00, 0x00, 0x00) },
{ TagGPSLatitude,
TiffTypeRational, 3,
IFD_SET_OFFSET(JpegExifHdr::TiffData, ifd_gps_data.latitude) },
#define TAG_GPS_LONGITUDE_REF_IDX 3
{ TagGPSLongitudeRef,
TiffTypeAscii, 2,
IFD_SET_UNDEF(0x00, 0x00, 0x00, 0x00) },
{ TagGPSLongitude,
TiffTypeRational, 3,
IFD_SET_OFFSET(JpegExifHdr::TiffData, ifd_gps_data.longitude) },
#define TAG_GPS_ALTITUDE_REF_IDX 5
{ TagGPSAltitudeRef,
TiffTypeByte, 1,
IFD_SET_UNDEF(0x00, 0x00, 0x00, 0x00) },
{ TagGPSAltitude,
TiffTypeRational, 1,
IFD_SET_OFFSET(JpegExifHdr::TiffData, ifd_gps_data.altitude) },
{ TagGPSTimeStamp,
TiffTypeRational, 3,
IFD_SET_OFFSET(JpegExifHdr::TiffData, ifd_gps_data.time_stamp) },
#define TAG_GPS_STATUS_IDX 8
{ TagGPSStatus,
TiffTypeAscii, 2,
IFD_SET_UNDEF('V', 0x00, 0x00, 0x00) },
/*TODO: currently not available from MicroNMEA
{ TagGPSMeasureMode,
TiffTypeAscii, 2,
IFD_SET_UNDEF('2', 0x00, 0x00, 0x00) },*/
{ TagGPSMapDatum,
TiffTypeAscii,
sizeof(exif_hdr.tiff_data.ifd_gps_data.map_datum),
IFD_SET_OFFSET(JpegExifHdr::TiffData, ifd_gps_data.map_datum) },
{ TagGPSProcessingMethod,
TiffTypeUndef,
sizeof(exif_hdr.tiff_data.ifd_gps_data.processing_method),
IFD_SET_OFFSET(JpegExifHdr::TiffData, ifd_gps_data.processing_method) },
{ TagGPSDateStamp,
TiffTypeAscii,
sizeof(exif_hdr.tiff_data.ifd_gps_data.date_stamp),
IFD_SET_OFFSET(JpegExifHdr::TiffData, ifd_gps_data.date_stamp) },
},
.next_ifd = 0
},
.ifd_gps_data = {
{ { 0, 1000*1000 }, { 0, 1 }, { 0, 1 } },
{ { 0, 1000*1000 }, { 0, 1 }, { 0, 1 } },
{ 0, 1000 },
{ { 0, 1 }, { 0, 1 }, { 0, 1 } },
GPS_MAP_DATUM,
{ 0x41, 0x53, 0x43, 0x49, 0x49, 0x00, 0x00, 0x00, 'G', 'P', 'S' },
" : : ",
}
#endif // WITH_GNSS
}
};
#pragma pack()
bool update_exif_from_cfg(const uint8_t c)
{
exif_hdr.tiff_data.ifd0.entries[TAG_IFD0_ORIENTATION_IDX].value = IFD_SET_SHORT(c);
return true;
}
#ifdef WITH_GNSS
void update_exif_gps(const MicroNMEA& nmea)
{
// Latitude
long lat = nmea.getLatitude();
if (lat < 0) {
exif_hdr.tiff_data.ifd_gps.entries[TAG_GPS_LATITUDE_REF_IDX].value = IFD_SET_BYTE('S');
lat *= -1;
} else {
exif_hdr.tiff_data.ifd_gps.entries[TAG_GPS_LATITUDE_REF_IDX].value = IFD_SET_BYTE('N');
}
exif_hdr.tiff_data.ifd_gps_data.latitude[0].num = lat;
// Longitude
long lon = nmea.getLongitude();
if (lon < 0) {
exif_hdr.tiff_data.ifd_gps.entries[TAG_GPS_LONGITUDE_REF_IDX].value = IFD_SET_BYTE('W');
lon *= -1;
} else {
exif_hdr.tiff_data.ifd_gps.entries[TAG_GPS_LONGITUDE_REF_IDX].value = IFD_SET_BYTE('E');
}
exif_hdr.tiff_data.ifd_gps_data.longitude[0].num = lon;
// Altitude
long alt;
if (nmea.getAltitude(alt)) {
if (alt < 0) {
exif_hdr.tiff_data.ifd_gps.entries[TAG_GPS_ALTITUDE_REF_IDX].value = IFD_SET_BYTE(1);
alt *= -1;
} else {
exif_hdr.tiff_data.ifd_gps.entries[TAG_GPS_ALTITUDE_REF_IDX].value = IFD_SET_BYTE(0);
}
exif_hdr.tiff_data.ifd_gps_data.altitude.num = alt;
} else {
exif_hdr.tiff_data.ifd_gps_data.altitude.num = 0;
}
// time stamp
exif_hdr.tiff_data.ifd_gps_data.time_stamp[0].num = nmea.getHour();
exif_hdr.tiff_data.ifd_gps_data.time_stamp[1].num = nmea.getMinute();
exif_hdr.tiff_data.ifd_gps_data.time_stamp[2].num = nmea.getSecond();
// GPS Status
if (nmea.isValid()) {
exif_hdr.tiff_data.ifd_gps.entries[TAG_GPS_STATUS_IDX].value = IFD_SET_BYTE('A');
} else {
exif_hdr.tiff_data.ifd_gps.entries[TAG_GPS_STATUS_IDX].value = IFD_SET_BYTE('V');
}
// date stamp
snprintf(exif_hdr.tiff_data.ifd_gps_data.date_stamp,
sizeof(exif_hdr.tiff_data.ifd_gps_data.date_stamp),
"%04u:%02u:%02u",
nmea.getYear(),
nmea.getMonth(),
nmea.getDay());
}
#endif // WITH_GNSS
const uint8_t *get_exif_header(camera_fb_t *fb, const uint8_t **exif_buf, size_t *exif_len)
{
// TODO: pass config to function and use that to set some of the image
// taking conditions. Or do this only once, with a update config
// function????
// Get current time
struct timeval now_tv;
if (gettimeofday(&now_tv, NULL) != 0) {
now_tv.tv_sec = time(NULL);
now_tv.tv_usec = 0;
}
// Set date time
struct tm timeinfo;
localtime_r(&now_tv.tv_sec, &timeinfo);
strftime(exif_hdr.tiff_data.ifd0_data.datetime, sizeof(exif_hdr.tiff_data.ifd0_data.datetime), "%Y:%m:%d %H:%M:%S", &timeinfo);
// Set sub-seconds time
snprintf( (char *) &(exif_hdr.tiff_data.ifd_exif.entries[TAG_EXIF_SUBSEC_TIME_IDX].value), 9, "%03ld", now_tv.tv_usec/1000);
// Update image dimensions
exif_hdr.tiff_data.ifd_exif.entries[TAG_EXIF_PIXEL_X_DIMENSION_IDX].value = IFD_SET_SHORT(fb->width);
exif_hdr.tiff_data.ifd_exif.entries[TAG_EXIF_PIXEL_Y_DIMENSION_IDX].value = IFD_SET_SHORT(fb->height);
*exif_len = sizeof(exif_hdr);
if (exif_buf != NULL) {
*exif_buf = (uint8_t *) &exif_hdr;
}
return (uint8_t *) &exif_hdr;
}
size_t get_jpeg_data_offset(camera_fb_t *fb)
{
if (fb->len < 6) {
return 0;
}
// Check JPEG SOI
if (fb->buf[0] != 0xff || fb->buf[1] != 0xd8) {
return 0;
}
size_t data_offset = 2; // Offset to first JPEG segment after header
// Check if JFIF header
if (fb->buf[2] == 0xff && fb->buf[3] == 0xe0) {
uint16_t jfif_len = fb->buf[4] << 8 | fb->buf[5];
data_offset += 2 + jfif_len;
}
if (data_offset >= fb->len) {
return 0;
}
return data_offset;
}

View File

@ -1,91 +0,0 @@
/**
* exif.h - Functions to generate Exif metadata
*
* Copyright (c) 2019, David Imhoff <dimhoff.devel@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the author nor the names of its contributors may
* be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO
* EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
* OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
* OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
* ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
* Project URL: https://github.com/dimhoff/ESP32-CAM_Interval
*
*/
#ifndef __EXIF_H__
#define __EXIF_H__
#include <stdint.h>
#include <stddef.h>
#include "esp_camera.h"
#ifdef WITH_GNSS
# include <MicroNMEA.h>
#endif
#include "mcu_cfg.h"
/**
* Update the configurable EXIF header fields
*
* Update all field in the EXIF header that depend on the configuration. Needs
* to be called every time the configuration is changed.
*
* @returns True on success, else false
*/
bool update_exif_from_cfg(const uint8_t);
#ifdef WITH_GNSS
/**
* Update GPS data in EXIF header
*
* Should be called for every call to get_exif_header() if GNSS support is enabled.
*/
void update_exif_gps(const MicroNMEA& nmea);
#endif // WITH_GNSS
/**
* Get Exif header
*
* Get a buffer with a new Exif header that can be prepended to a JPEG image.
* The JPEG does need to be stripped from its original header first, see
* get_jpeg_data_offset().
*
* The returned pointer point so a static buffer, and should not be altered.
* This function is not reentrant safe.
*
* @param fb Frame buffer of captured image. Encoding is expected to
* be JPEG
* @param exif_buf If not NULL, used to return pointer to Exif buffer in
* @param exif_buf Used to return the size of the Exif buffer
*
* @returns Pointer to Exif buffer, or NULL on error
*/
const uint8_t *get_exif_header(camera_fb_t *fb, const uint8_t **exif_buf, size_t *exif_len);
/**
* Get offset of first none header byte in buffer
*
* Get the offset of the first none JPEG header byte in capture buffer. This
* can be used to strip the JPEG SOI and JFIF headers from an image.
*
* @returns offset of first non header byte, or 0 on error
*/
size_t get_jpeg_data_offset(camera_fb_t *fb);
#endif // __EXIF_H__

View File

@ -1,214 +0,0 @@
/**
* exif_defines.h - Defines for constants from Exif v2.3 standard
*
* Written 2019, David Imhoff <dimhoff.devel@gmail.com>
*
* This is free and unencumbered software released into the public domain.
*
* Anyone is free to copy, modify, publish, use, compile, sell, or
* distribute this software, either in source code form or as a compiled
* binary, for any purpose, commercial or non-commercial, and by any
* means.
*
* In jurisdictions that recognize copyright laws, the author or authors
* of this software dedicate any and all copyright interest in the
* software to the public domain. We make this dedication for the benefit
* of the public at large and to the detriment of our heirs and
* successors. We intend this dedication to be an overt act of
* relinquishment in perpetuity of all present and future rights to this
* software under copyright law.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.
* IN NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY CLAIM, DAMAGES OR
* OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
* ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
* OTHER DEALINGS IN THE SOFTWARE.
*/
#ifndef __EXIF_DEFINES_H__
#define __EXIF_DEFINES_H__
// TIFF Rev. 6.0 Attribute Information Used in Exif
enum {
// A. Tags relating to image data structure
TagTiffImageWidth = 0x100, // Image width
TagTiffImageLength = 0x101, // Image height
TagTiffBitsPerSample = 0x102, // Number of bits per component
TagTiffCompression = 0x103, // Compression scheme
TagTiffPhotometricInterpretation = 0x106, // Pixel composition
TagTiffOrientation = 0x112, // Orientation of image
TagTiffSamplesPerPixel = 0x115, // Number of components
TagTiffPlanarConfiguration = 0x11C, // Image data arrangement
TagTiffYCbCrSubSampling = 0x212, // Subsampling ratio of Y to C
TagTiffYCbCrPositioning = 0x213, // Y and C positioning
TagTiffXResolution = 0x11A, // Image resolution in width direction
TagTiffYResolution = 0x11B, // Image resolution in height direction
TagTiffResolutionUnit = 0x128, // Unit of X and Y resolution
// B. Tags relating to recording offset
TagTiffStripOffsets = 0x111, // Image data location
TagTiffRowsPerStrip = 0x116, // Number of rows per strip
TagTiffStripByteCounts = 0x117, // Bytes per compressed strip
TagTiffJPEGInterchangeFormat = 0x201, // Offset to JPEG SOI
TagTiffJPEGInterchangeFormatLength = 0x202, // Bytes of JPEG data
// C. Tags relating to image data characteristics
TagTiffTransferFunction = 0x12D, // Transfer function
TagTiffWhitePoint = 0x13E, // White point chromaticity
TagTiffPrimaryChromaticities = 0x13F, // Chromaticities of primaries
TagTiffYCbCrCoefficients = 0x211, // Color space transformation matrix coefficients
TagTiffReferenceBlackWhite = 0x214, // Pair of black and white reference values
// D. Other tags
TagTiffDateTime = 0x132, // File change date and time
TagTiffImageDescription = 0x10E, // Image title
TagTiffMake = 0x10F, // Image input equipment manufacturer
TagTiffModel = 0x110, // Image input equipment model
TagTiffSoftware = 0x131, // Software used
TagTiffArtist = 0x13B, // Person who created the image
TagTiffCopyright = 0x8298, // Copyright holder
// Exif private IFD's
TagTiffExifIFD = 0x8769, // Exif IFD pointer
TagTiffGPSIFD = 0x8825, // Exif IFD pointer
TagTiffInteroperabilityIFD = 0xA005, // Exif IFD pointer
};
// Exif IFD Attribute Information
enum {
// Tags Relating to Version
TagExifVersion = 0x9000, // Exif version
TagExifFlashpixVersion = 0xA000, // Supported Flashpix version
// Tag Relating to Image Data Characteristics
TagExifColorSpace = 0xA001, // Color space information
TagExifGamma = 0xA500, // Gamma
// Tags Relating to Image Configuration
TagExifComponentsConfiguration = 0x9101, // Meaning of each component
TagExifCompressedBitsPerPixel = 0x9102, // Image compression mode
TagExifPixelXDimension = 0xA002, // Valid image width
TagExifPixelYDimension = 0xA003, // Valid image height
// Tags Relating to User Information
TagExifMakerNote = 0x927C, // Manufacturer notes
TagExifUserComment = 0x9286, // User comments
// Tag Relating to Related File Information
TagExifRelatedSoundFile = 0xA004, // Related audio file
// Tags Relating to Date and Time
TagExifDateTimeOriginal = 0x9003, // Date and time of original data generation
TagExifDateTimeDigitized = 0x9004, // Date and time of digital data generation
TagExifSubSecTime = 0x9290, // DateTime subseconds
TagExifSubSecTimeOriginal = 0x9291, // DateTimeOriginal subseconds
TagExifSubSecTimeDigitized = 0x9292, // DateTimeDigitized subseconds
// Tags Relating to Picture-Taking Conditions
TagExifExposureTime = 0x829A, // Exposure time
TagExifFNumber = 0x829D, // F number
TagExifExposureProgram = 0x8822, // Exposure program
TagExifSpectralSensitivity = 0x8824, // Spectral sensitivity
TagExifPhotographicSensitivity = 0x8827, // Photographic Sensitivity
TagExifOECF = 0x8828, // Optoelectric conversion factor
TagExifSensitivityType = 0x8830, // Sensitivity Type
TagExifStandardOutputSensitivity = 0x8831, // Standard Output Sensitivity
TagExifRecommendedExposureIndex = 0x8832, // Recommended ExposureIndex
TagExifISOSpeed = 0x8833, // ISO Speed
TagExifISOSpeedLatitudeyyy = 0x8834, // ISO Speed Latitude yyy
TagExifISOSpeedLatitudezzz = 0x8835, // ISO Speed Latitude zzz
TagExifShutterSpeedValue = 0x9201, // Shutter speed
TagExifApertureValue = 0x9202, // Aperture
TagExifBrightnessValue = 0x9203, // Brightness
TagExifExposureBiasValue = 0x9204, // Exposure bias
TagExifMaxApertureValue = 0x9205, // Maximum lens aperture
TagExifSubjectDistance = 0x9206, // Subject distance
TagExifMeteringMode = 0x9207, // Metering mode
TagExifLightSource = 0x9208, // Light source
TagExifFlash = 0x9209, // Flash
TagExifFocalLength = 0x920A, // Lens focal length
TagExifSubjectArea = 0x9214, // Subject area
TagExifFlashEnergy = 0xA20B, // Flash energy
TagExifSpatialFrequencyResponse = 0xA20C, // Spatial frequency response
TagExifFocalPlaneXResolution = 0xA20E, // Focal plane X resolution
TagExifFocalPlaneYResolution = 0xA20F, // Focal plane Y resolution
TagExifFocalPlaneResolutionUnit = 0xA210, // Focal plane resolution unit
TagExifSubjectLocation = 0xA214, // Subject location
TagExifExposureIndex = 0xA215, // Exposure index
TagExifSensingMethod = 0xA217, // Sensing method
TagExifFileSource = 0xA300, // File source
TagExifSceneType = 0xA301, // Scene type
TagExifCFAPattern = 0xA302, // CFA pattern
TagExifCustomRendered = 0xA401, // Custom image processing
TagExifExposureMode = 0xA402, // Exposure mode
TagExifWhiteBalance = 0xA403, // White balance
TagExifDigitalZoomRatio = 0xA404, // Digital zoom ratio
TagExifFocalLengthIn35mmFilm = 0xA405, // Focal length in 35 mm film
TagExifSceneCaptureType = 0xA406, // Scene capture type
TagExifGainControl = 0xA407, // Gain control
TagExifContrast = 0xA408, // Contrast
TagExifSaturation = 0xA409, // Saturation
TagExifSharpness = 0xA40A, // Sharpness
TagExifDeviceSettingDescription = 0xA40B, // Device settings description
TagExifSubjectDistanceRange = 0xA40C, // Subject distance range
// Other Tags
TagExifImageUniqueID = 0xA420, // Unique image ID
TagExifCameraOwnerName = 0xA430, // Camera Owner Name
TagExifBodySerialNumber = 0xA431, // Body Serial Number
TagExifLensSpecification = 0xA432, // Lens Specification
TagExifLensMake = 0xA433, // Lens Make
TagExifLensModel = 0xA434, // Lens Model
TagExifLensSerialNumber = 0xA435, // Lens Serial Number
};
// GPS Attribute Information
enum {
TagGPSVersionID = 0x00, // GPS tag version
TagGPSLatitudeRef = 0x01, // North or South Latitude
TagGPSLatitude = 0x02, // Latitude
TagGPSLongitudeRef = 0x03, // East or West Longitude
TagGPSLongitude = 0x04, // Longitude
TagGPSAltitudeRef = 0x05, // Altitude reference
TagGPSAltitude = 0x06, // Altitude
TagGPSTimeStamp = 0x07, // GPS time (atomic clock)
TagGPSSatellites = 0x08, // GPS satellites used for measurement
TagGPSStatus = 0x09, // GPS receiver status
TagGPSMeasureMode = 0x0A, // GPS measurement mode
TagGPSDOP = 0x0B, // Measurement precision
TagGPSSpeedRef = 0x0C, // Speed unit
TagGPSSpeed = 0x0D, // Speed of GPS receiver
TagGPSTrackRef = 0x0E, // Reference for direction of movement
TagGPSTrack = 0x0F, // Direction of movement
TagGPSImgDirectionRef = 0x10, // Reference for direction of image
TagGPSImgDirection = 0x11, // Direction of image
TagGPSMapDatum = 0x12, // Geodetic survey data used
TagGPSDestLatitudeRef = 0x13, // Reference for latitude of destination
TagGPSDestLatitude = 0x14, // Latitude of destination
TagGPSDestLongitudeRef = 0x15, // Reference for longitude of destination
TagGPSDestLongitude = 0x16, // Longitude of destination
TagGPSDestBearingRef = 0x17, // Reference for bearing of destination
TagGPSDestBearing = 0x18, // Bearing of destination
TagGPSDestDistanceRef = 0x19, // Reference for distance to destination
TagGPSDestDistance = 0x1A, // Distance to destination
TagGPSProcessingMethod = 0x1B, // Name of GPS processing method
TagGPSAreaInformation = 0x1C, // Name of GPS area
TagGPSDateStamp = 0x1D, // GPS date
TagGPSDifferential = 0x1E, // GPS differential correction
TagGPSHPositioningError = 0x1F, // Horizontal positioning error
};
// TIFF type fields values
enum {
TiffTypeByte = 1,
TiffTypeAscii = 2,
TiffTypeShort = 3,
TiffTypeLong = 4,
TiffTypeRational = 5,
TiffTypeUndef = 7,
TiffTypeSLong = 9,
TiffTypeSRational = 10,
};
#endif // __EXIF_DEFINES_H__

File diff suppressed because one or more lines are too long

View File

@ -18,13 +18,11 @@ Logs SystemLog(LOGS_FILE_PATH, LOGS_FILE_NAME, LOGS_FILE_MAX_SIZE);
@return none
*/
Logs::Logs() {
FileName = F("log.txt");
FilePath = F("/");
FileName = "log.txt";
FilePath = "/";
LogLevel = LogLevel_Verbose;
FileMaxSize = 1024;
NtpTimeSynced = false;
LogMsg = "";
LogMutex = xSemaphoreCreateMutex();
}
/**
@ -39,8 +37,6 @@ Logs::Logs(String i_FilePath, String i_FileName) {
LogLevel = LogLevel_Verbose;
FileMaxSize = 1024;
NtpTimeSynced = false;
LogMsg = "";
LogMutex = xSemaphoreCreateMutex();
}
/**
@ -56,8 +52,6 @@ Logs::Logs(LogLevel_enum i_LogLevel, String i_FilePath, String i_FileName) {
LogLevel = i_LogLevel;
FileMaxSize = 1024;
NtpTimeSynced = false;
LogMsg = "";
LogMutex = xSemaphoreCreateMutex();
}
/**
@ -73,8 +67,6 @@ Logs::Logs(String i_FilePath, String i_FileName, uint16_t i_FileSize) {
LogLevel = LogLevel_Verbose;
FileMaxSize = i_FileSize;
NtpTimeSynced = false;
LogMsg = "";
LogMutex = xSemaphoreCreateMutex();
}
/**
@ -91,8 +83,6 @@ Logs::Logs(LogLevel_enum i_LogLevel, String i_FilePath, String i_FileName, uint1
LogLevel = i_LogLevel;
FileMaxSize = i_FileSize;
NtpTimeSynced = false;
LogMsg = "";
LogMutex = xSemaphoreCreateMutex();
}
/**
@ -107,66 +97,36 @@ void Logs::Init() {
Serial.println(F("Init Logs library"));
/* init micro SD card */
#if (true == ENABLE_SD_CARD)
InitSdCard();
LogFileOpened = OpenFile(&LogFile, FilePath + FileName);
if (true == GetCardDetectedStatus()) {
/* check maximum log file size */
CheckMaxLogFileSize();
uint32_t FileSize = GetFileSize(SD_MMC, FilePath + FileName);
Serial.printf("Log file size: %d\n", FileSize);
if (FileSize >= LOGS_FILE_MAX_SIZE) {
uint16_t file_count = FileCount(SD_MMC, FilePath, FileName);
Serial.printf("Maximum log file size.\nFile count: %d\n", file_count);
RenameFile(SD_MMC, FilePath + FileName, FilePath + FileName + String(file_count));
}
/* added first message to log file after start MCU */
LogMsg = F("----------------------------------------------------------------\n");
LogMsg += F("Start MCU!\nSW Version: ");
LogMsg += String(SW_VERSION);
LogMsg += F(" ,Build: ");
LogMsg += String(SW_BUILD);
LogMsg += "\n";
LogMsg += F("Verbose mode: ");
LogMsg += (true == CONSOLE_VERBOSE_DEBUG) ? "true" : "false";
LogMsg += "\n";
LogMsg += F("Log level: ");
LogMsg += String(LogLevel);
LogMsg += "\n";
AppendFile(&LogFile, &LogMsg);
String msg = F("----------------------------------------------------------------\n");
msg += F("Start MCU!\nSW Version: ");
msg += String(SW_VERSION);
msg += F(" ,Build: ");
msg += String(SW_BUILD);
msg += "\n";
msg += F("Verbose mode: ");
msg += (true == CONSOLE_VERBOSE_DEBUG) ? "true" : "false";
msg += "\n";
msg += F("Log level: ");
msg += String(LogLevel);
msg += "\n";
AppendFile(SD_MMC, FilePath + FileName, msg);
} else {
Serial.println(F("Micro-SD card not found! Disable logs"));
}
#else
Serial.println(F("Micro-SD card not enabled! Disable logs to card"));
LogFileOpened = false;
#endif
}
/**
* @brief Open log file
*
*/
void Logs::LogOpenFile() {
#if (true == ENABLE_SD_CARD)
LogFileOpened = OpenFile(&LogFile, FilePath + FileName);
#endif
}
/**
* @brief Close log file
*
*/
void Logs::LogCloseFile() {
#if (true == ENABLE_SD_CARD)
CloseFile(&LogFile);
#endif
}
/**
* @brief Function for check opened log file
*
*/
void Logs::LogCheckOpenedFile() {
#if (true == ENABLE_SD_CARD)
LogFileOpened = CheckOpenFile(&LogFile);
#endif
}
/**
@ -187,13 +147,9 @@ void Logs::SetLogLevel(LogLevel_enum level) {
@return none
*/
void Logs::AddEvent(LogLevel_enum level, String msg, bool newLine, bool date) {
/* mutex for log */
xSemaphoreTake(LogMutex, portMAX_DELAY);
/* check log level */
if (LogLevel >= level) {
String LogMsg = "";
/* create log message */
LogMsg = "";
if (true == date) {
LogMsg += GetSystemTime();
LogMsg += " - ";
@ -203,85 +159,16 @@ void Logs::AddEvent(LogLevel_enum level, String msg, bool newLine, bool date) {
LogMsg += "\n";
}
/* print log message to console */
AppendFile(SD_MMC, FilePath + FileName, LogMsg);
Serial.print(LogMsg);
#if (true == ENABLE_SD_CARD)
/* append log message to log file */
if (true == LogFileOpened) {
LogFileOpened = AppendFile(&LogFile, &LogMsg);
if ((false == LogFileOpened) && (true == GetCardDetectedStatus())){
LogCloseFile();
LogOpenFile();
if (true == LogFileOpened) {
LogFileOpened = AppendFile(&LogFile, &LogMsg);
}
}
}
#endif
}
#if (true == CONSOLE_VERBOSE_DEBUG)
else {
Serial.println(msg);
}
#endif
xSemaphoreGive(LogMutex);
}
/**
@info Add new log event
@param LogLevel_enum - log level
@param const __FlashStringHelper - log message
@param String - parameters
@param bool - new line
@param bool - date
@return none
*/
void Logs::AddEvent(LogLevel_enum level, const __FlashStringHelper *msg, String parameters, bool newLine, bool date) {
/* mutex for log */
xSemaphoreTake(LogMutex, portMAX_DELAY);
/* check log level */
if (LogLevel >= level) {
/* create log message */
LogMsg = "";
if (true == date) {
LogMsg += GetSystemTime();
LogMsg += " - ";
}
LogMsg += msg;
LogMsg += parameters;
if (true == newLine) {
LogMsg += "\n";
}
/* print log message to console */
Serial.print(LogMsg);
#if (true == ENABLE_SD_CARD)
/* append log message to log file */
if (true == LogFileOpened) {
LogFileOpened = AppendFile(&LogFile, &LogMsg);
if ((false == LogFileOpened) && (true == GetCardDetectedStatus())){
LogCloseFile();
LogOpenFile();
if (true == LogFileOpened) {
AppendFile(&LogFile, &LogMsg);
}
}
}
#endif
}
#if (true == CONSOLE_VERBOSE_DEBUG)
else {
Serial.println(msg);
}
#endif
/* release mutex */
xSemaphoreGive(LogMutex);
}
/**
@info Set file name
@param String - file name
@ -316,7 +203,7 @@ void Logs::SetFileMaxSize(uint16_t i_data) {
*/
void Logs::SetNtpTimeSynced(bool i_data) {
NtpTimeSynced = i_data;
AddEvent(LogLevel_Info, F("System time: "), GetSystemTime());
AddEvent(LogLevel_Info, "System time: " + GetSystemTime());
}
/**
@ -355,42 +242,6 @@ bool Logs::GetNtpTimeSynced() {
return NtpTimeSynced;
}
/**
@info Check maximum log file size
@param none
@return none
*/
void Logs::CheckMaxLogFileSize() {
#if (true == ENABLE_SD_CARD)
uint32_t FileSize = GetFileSize(SD_MMC, FilePath + FileName);
AddEvent(LogLevel_Verbose, F("Log file size: "), String(FileSize) + "/" + String(LOGS_FILE_MAX_SIZE) + " B");
if (FileSize >= LOGS_FILE_MAX_SIZE) {
uint16_t file_count = FileCount(SD_MMC, FilePath, FileName);
AddEvent(LogLevel_Info, F("Maximum log file size. File count: "), String(file_count));
LogCloseFile();
RenameFile(SD_MMC, FilePath + FileName, FilePath + FileName + String(file_count));
LogOpenFile();
}
#endif
}
void Logs::CheckCardSpace() {
#if (true == ENABLE_SD_CARD)
CheckCardUsedStatus();
AddEvent(LogLevel_Verbose, "Card size: " + String(GetCardSizeMB()), + " MB, Used: " + String(GetCardUsedMB()) + " MB, Free: " + String(GetCardUsedMB()) + " MB");
#endif
}
/**
@info Get log file opened
@param none
@return bool - log file opened
*/
bool Logs::GetLogFileOpened() {
return LogFileOpened;
}
/**
@info Get system time
@param none

View File

@ -9,24 +9,29 @@
@bug: no know bug
*/
#pragma once
#ifndef _LOG_H_
#define _LOG_H_
#include <Arduino.h>
#include "Arduino.h"
#include "mcu_cfg.h"
#include "var.h"
#include "micro_sd.h"
#include "log_level.h"
enum LogLevel_enum {
LogLevel_Error = 0, ///< Error
LogLevel_Warning = 1, ///< Warning
LogLevel_Info = 2, ///< Info
LogLevel_Verbose = 3 ///< Verbose
};
class Logs : public MicroSd {
private:
LogLevel_enum LogLevel; ///< LogLevel
String FileName; ///< log File name
String FilePath; ///< log file patch
uint16_t FileMaxSize; ///< log file max size
bool NtpTimeSynced; ///< status NTP time sync
String LogMsg; ///< log message
File LogFile; ///< log file object
bool LogFileOpened; ///< log file opened status
SemaphoreHandle_t LogMutex; ///< log mutex
LogLevel_enum LogLevel; ///< LogLevel
String FileName; ///< log File name
String FilePath; ///< log file patch
uint16_t FileMaxSize; ///< log file max size
bool NtpTimeSynced; ///< status NTP time sync
public:
Logs();
@ -37,11 +42,7 @@ public:
~Logs(){};
void Init();
void LogOpenFile();
void LogCloseFile();
void LogCheckOpenedFile();
void AddEvent(LogLevel_enum, String, bool = true, bool = true);
void AddEvent(LogLevel_enum, const __FlashStringHelper*, String, bool = true, bool = true);
void SetLogLevel(LogLevel_enum);
void SetFileName(String);
void SetFilePath(String);
@ -52,13 +53,13 @@ public:
String GetFilePath();
LogLevel_enum GetLogLevel();
bool GetNtpTimeSynced();
void CheckMaxLogFileSize();
void CheckCardSpace();
bool GetLogFileOpened();
protected:
String GetSystemTime();
};
extern Logs SystemLog; ///< log object
#endif
/* EOF */

View File

@ -1,10 +0,0 @@
#pragma once
enum LogLevel_enum {
LogLevel_Error = 0, ///< Error
LogLevel_Warning = 1, ///< Warning
LogLevel_Info = 2, ///< Info
LogLevel_Verbose = 3 ///< Verbose
};
/* EOF */

View File

@ -7,26 +7,17 @@
Contact: miroslav.pivovarsky@gmail.com
@bug: no know bug
*/
#ifndef _MCU_CFG_H_
#define _MCU_CFG_H_
/* ----------------- CAMERA TYPE ---------------*/
#define AI_THINKER_ESP32_CAM true
#define ESP32_WROVER_DEV false
#define CAMERA_MODEL_ESP32_S3_DEV_CAM false
#define CAMERA_MODEL_ESP32_S3_EYE_2_2 false
#define CAMERA_MODEL_XIAO_ESP32_S3_CAM false
#define CAMERA_MODEL_ESP32_S3_CAM false
#define ESP32_S3_WROOM_FREENOVE false
/* ---------------- BASIC MCU CFG --------------*/
#define SW_VERSION "1.1.2" ///< SW version
#define SW_VERSION "1.0.2-rc1" ///< SW version
#define SW_BUILD __DATE__ " " __TIME__ ///< build number
#define CONSOLE_VERBOSE_DEBUG false ///< enable/disable verbose debug log level for console
#define DEVICE_HOSTNAME "Prusa-ESP32cam" ///< device hostname
#define CAMERA_MAX_FAIL_CAPTURE 10 ///< maximum count for failed capture
/* ------------ PRUSA BACKEND CFG --------------*/
#define HOST_URL_CAM_PATH "/c/snapshot" ///< path for sending photo to prusa connect
@ -34,7 +25,17 @@
#define REFRESH_INTERVAL_MIN 10 ///< minimum refresh interval for sending photo to prusa connect [s]
#define REFRESH_INTERVAL_MAX 240 ///< maximum refresh interval for sending photo to prusa connect [s]
/* --------------- FLASH LED CFG ---------------*/
#define FLASH_GPIO_NUM 4 ///< GPIO pin for light
#define FLASH_OFF_STATUS 0 ///< PWM intensity LED for OFF. 0-2^FLASH_PWM_RESOLUTION = 0-255
#define FLASH_ON_STATUS 205 ///< PWM intensity LED for ON. limitation to 80%. 2^FLASH_PWM_RESOLUTION * 0.8% = 204
#define FLASH_PWM_FREQ 2000 ///< frequency of pwm [240MHz / (100 prescale * pwm cycles)] = frequency
#define FLASH_PWM_CHANNEL 0 ///< channel 0
#define FLASH_PWM_RESOLUTION 8 ///< range 1-20bit. 8bit = 0-255 range
/* -------------- STATUS LED CFG ----------------*/
#define STATUS_LED_GPIO_NUM 33 ///< GPIO pin for status LED
#define STATUS_LED_ENABLE true ///< enable/disable status LED
#define STATUS_LED_ON_DURATION 100 ///< time for blink status LED when is module in the ON state [ms]
#define STATUS_LED_WIFI_AP 400 ///< time for blink status LED when is module in the AP mode [ms]
#define STATUS_LED_STA_CONNECTING 800 ///< time for blink status LED when is module connecting to the WiFi network [ms]
@ -43,28 +44,30 @@
/* ------------------- TASKS --------------------*/
#define TASK_SYSTEM 1000 ///< system task interval [ms]
#define TASK_SDCARD 25000 ///< sd card task interval [ms]
#define TASK_WIFI 28000 ///< wifi reconnect interval. Checking when is signal lost [ms]
#define TASK_SDCARD 30000 ///< sd card task interval [ms]
#define TASK_WIFI 30000 ///< wifi reconnect interval. Checking when is signal lost [ms]
#define TASK_SERIAL_CFG 1000 ///< serial cfg task interval [ms]
#define TASK_SYSTEM_TELEMETRY 30000 ///< stream telemetry task interval [ms]
#define TASK_STREAM_TELEMETRY 30000 ///< stream telemetry task interval [ms]
#define TASK_WIFI_WATCHDOG 20000 ///< wifi watchdog task interval [ms]
#define TASK_PHOTO_SEND 1000 ///< photo send task interval [ms]
#define TASK_SDCARD_FILE_REMOVE 30000 ///< sd card file remove task interval [ms]
/* --------------- WEB SERVER CFG --------------*/
#define WEB_SERVER_PORT 80 ///< WEB server port
#define SERIAL_PORT_SPEED 115200 ///< baud rate
#define WDG_TIMEOUT 40000 ///< wdg timeout [second]
#define PHOTO_FRAGMENT_SIZE 2048 ///< photo fragmentation size [bytes]
#define WDG_TIMEOUT 40 ///< wdg timeout [second]
#define PHOTO_FRAGMENT_SIZE 5000 ///< photo fragmentation size [bytes]
#define LOOP_DELAY 100 ///< loop delay [ms]
#define WIFI_CLIENT_WAIT_CON false ///< wait for connecting to WiFi network
#define DYNMIC_JSON_SIZE 1024 ///< maximum size for dynamic json [bytes]
#define WEB_CACHE_INTERVAL 86400 ///< cache interval for browser [s] 86400s = 24h
/* --------------- OTA UPDATE CFG --------------*/
#define OTA_UPDATE_API_SERVER "api.github.com" ///< OTA update server URL
#define OTA_UPDATE_API_URL F("/repos/prusa3d/Prusa-Firmware-ESP32-Cam/releases/latest") ///< path to file with OTA update
#define OTA_UPDATE_API_URL "/repos/prusa3d/Prusa-Firmware-ESP32-Cam/releases/latest" ///< path to file with OTA update
#define OTA_UPDATE_FW_FILE "ESP32_PrusaConnectCam.ino.bin" ///< OTA update firmware file name
/* ---------- RESET CFG CONFIGURATION ----------*/
#define CFG_RESET_PIN 12 ///< GPIO 16 is for reset CFG to default
#define CFG_RESET_TIME_WAIT 10000 ///< wait to 10 000 ms = 10s for reset cfg during grounded CFG_RESET_PIN
#define CFG_RESET_LOOP_DELAY 100 ///< delay in the loop for reset cfg
@ -72,25 +75,23 @@
#define LOGS_FILE_NAME "SysLog.log" ///< syslog file name
#define LOGS_FILE_PATH "/" ///< directory for log files
#define LOGS_FILE_MAX_SIZE 1024 ///< maximum file size in the [kb]
#define FILE_REMOVE_MAX_COUNT 5 ///< maximum count for remove files from sd card
/* ---------------- AP MODE CFG ----------------*/
#define STA_AP_MODE_TIMEOUT 300000 ///< how long is AP enable after start, when is module in the STA mode [ms]
#define SERVICE_WIFI_SSID_UID true ///< enable/disable added UID to service SSID name
#define SERVICE_WIFI_SSID F("ESP32_camera") ///< service WI-FI SSID name. Maximum length SERVICE_WIFI_SSID + UID = 32
#define SERVICE_WIFI_PASS F("12345678") ///< service WI-FI password
#define SERVICE_WIFI_SSID "ESP32_camera" ///< service WI-FI SSID name. Maximum length SERVICE_WIFI_SSID + UID = 32
#define SERVICE_WIFI_PASS "12345678" ///< service WI-FI password
#define SERVICE_WIFI_CHANNEL 10 ///< service WI-FI channel
#define SERVICE_LOCAL_IP F("192.168.0.1") ///< service WI-FI module IP address
#define SERVICE_LOCAL_GATEWAY F("192.168.0.1") ///< service WI-FI module gateway
#define SERVICE_LOCAL_MASK F("255.255.255.0") ///< service WI-FI module mask
#define SERVICE_LOCAL_DNS F("192.168.0.1") ///< service WI-FI module DNS
#define SERVICE_LOCAL_IP "192.168.0.1" ///< service WI-FI module IP address
#define SERVICE_LOCAL_GATEWAY "192.168.0.1" ///< service WI-FI module gateway
#define SERVICE_LOCAL_MASK "255.255.255.0" ///< service WI-FI module mask
#define SERVICE_LOCAL_DNS "192.168.0.1" ///< service WI-FI module DNS
/* ----------------- IPv4 CFG -------------------*/
#define IPV4_ADDR_MAX_LENGTH 15 ///< maximum length for IPv4 address
/* ----------------- WiFi CFG -------------------*/
#define WIFI_STA_WDG_TIMEOUT 60000 ///< STA watchdog timeout [ms]
#define WIFI_DISABLE_UNENCRYPTED_STA_PASS_CHECK false ///< enable/disable WEP/WPA/WPA2/... encryption for STA mode . for the wifi network without encryption set to false
/* ----------------- NTP CFG --------------------*/
#define NTP_SERVER_1 "pool.ntp.org" ///< NTP server
@ -98,17 +99,6 @@
#define NTP_GTM_OFFSET_SEC 0 ///< GMT offset in seconds. 0 = UTC. 3600 = GMT+1
#define NTP_DAYLIGHT_OFFSET_SEC 0 ///< daylight offset in seconds. 0 = no daylight saving time. 3600 = +1 hour
/* ------------------ EXIF CFG ------------------*/
#define CAMERA_MAKE "OmniVision" ///< Camera make string
#define CAMERA_MODEL "OV2640" ///< Camera model string
#define CAMERA_SOFTWARE "Prusa ESP32-cam" ///< Camera software string
#define CAMERA_EXIF_ROTATION_STREAM false ///< enable camera exif rotation for stream
/* ---------------- TIMELAPS CFG ----------------*/
#define TIMELAPS_PHOTO_FOLDER "/timelapse" ///< folder for timelaps photos
#define TIMELAPS_PHOTO_PREFIX "photo" ///< photo name for timelaps
#define TIMELAPS_PHOTO_SUFFIX ".jpg" ///< photo file type for timelaps
/* ---------------- FACTORY CFG ----------------*/
#define FACTORY_CFG_PHOTO_REFRESH_INTERVAL 30 ///< in the second
#define FACTORY_CFG_PHOTO_QUALITY 10 ///< 10-63, lower is better
@ -126,28 +116,24 @@
#define FACTORY_CFG_BPC 1 ///< bad pixel detection
#define FACTORY_CFG_WPC 1 ///< white pixel correction
#define FACTORY_CFG_RAW_GAMA 1 ///< raw gama
#define FACTORY_CFG_WEB_AUTH_USERNAME F("admin") ///< user name for login to WEB interface. definition WEB_ENABLE_BASIC_AUTH must be true
#define FACTORY_CFG_WEB_AUTH_PASSWORD F("admin") ///< password for login to WEB interface. definition WEB_ENABLE_BASIC_AUTH must be true
#define FACTORY_CFG_WEB_AUTH_USERNAME "admin" ///< user name for login to WEB interface. definition WEB_ENABLE_BASIC_AUTH must be true
#define FACTORY_CFG_WEB_AUTH_PASSWORD "admin" ///< password for login to WEB interface. definition WEB_ENABLE_BASIC_AUTH must be true
#define FACTORY_CFG_WEB_AUTH_ENABLE false ///< enable web auth for login to WEB interface. definition WEB_ENABLE_BASIC_AUTH must be
#define FACTORY_CFG_CAMERA_FLASH_ENABLE false ///< enable camera flash functionality
#define FACTORY_CFG_CAMERA_FLASH_TIME 200 ///< time for camera flash duration time [ms]
#define FACTORY_CFG_MDNS_RECORD_HOST F("prusa-esp32cam") ///< mdns record http://MDNS_RECORD_HOST.local
#define FACTORY_CFG_MDNS_RECORD_HOST "prusa-esp32cam" ///< mdns record http://MDNS_RECORD_HOST.local
#define FACTORY_CFG_AEC2 0 ///< enable automatic exposition
#define FACTORY_CFG_AE_LEVEL 0 ///< automatic exposition level
#define FACTORY_CFG_AEC_VALUE 300 ///< automatic exposition time
#define FACTORY_CFG_GAIN_CTRL 1 ///< enable automatic gain
#define FACTORY_CFG_AGC_GAIN 0 ///< automatic gain controll gain
#define FACTORY_CFG_HOSTNAME F("connect.prusa3d.com") ///< hostname for Prusa Connect
#define FACTORY_CFG_HOSTNAME "connect.prusa3d.com" ///< hostname for Prusa Connect
#define FACTORY_CFG_ENABLE_SERVICE_AP 1 ///< enable service AP mode
#define FACTORY_CFG_NETWORK_IP_METHOD 0 ///< 0 - DHCP, 1 - Static IP
#define FACTORY_CFG_NETWORK_STATIC_IP F("255.255.255.255") ///< Static IP address
#define FACTORY_CFG_NETWORK_STATIC_MASK F("255.255.255.255") ///< Static Mask
#define FACTORY_CFG_NETWORK_STATIC_GATEWAY F("255.255.255.255") ///< Static Gateway
#define FACTORY_CFG_NETWORK_STATIC_DNS F("255.255.255.255") ///< Static DNS
#define FACTORY_CFG_IMAGE_EXIF_ROTATION 1 ///< Image rotation 1 - 0°, 6 - 90°, 3 - 180°, 8 - 270°
#define FACTORY_CFG_TIMELAPS_ENABLE 0 ///< enable timelaps functionality
#define FACTORY_CFG_ENABLE_EXT_SENSOR 0 ///< enable DHT22 sensor
#define FACTORY_CFG_EXT_SENSOR_UNIT 0 ///< 0 = celsius, 1 = fahrenheit
#define FACTORY_CFG_NETWORK_STATIC_IP "255.255.255.255" ///< Static IP address
#define FACTORY_CFG_NETWORK_STATIC_MASK "255.255.255.255" ///< Static Mask
#define FACTORY_CFG_NETWORK_STATIC_GATEWAY "255.255.255.255" ///< Static Gateway
#define FACTORY_CFG_NETWORK_STATIC_DNS "255.255.255.255" ///< Static DNS
/* ---------------- CFG FLAGS ------------------*/
#define CFG_WIFI_SETTINGS_SAVED 0x0A ///< flag saved config
@ -280,17 +266,6 @@
#define EEPROM_ADDR_NETWORK_STATIC_DNS_START (EEPROM_ADDR_NETWORK_STATIC_GATEWAY_START + EEPROM_ADDR_NETWORK_STATIC_GATEWAY_LENGTH)
#define EEPROM_ADDR_NETWORK_STATIC_DNS_LENGTH 4
#define EEPROM_ADDR_IMAGE_ROTATION_START (EEPROM_ADDR_NETWORK_STATIC_DNS_START + EEPROM_ADDR_NETWORK_STATIC_DNS_LENGTH)
#define EEPROM_ADDR_IMAGE_ROTATION_LENGTH 1
#define EEPROM_ADDR_TIMELAPS_ENABLE_START (EEPROM_ADDR_IMAGE_ROTATION_START + EEPROM_ADDR_IMAGE_ROTATION_LENGTH)
#define EEPROM_ADDR_TIMELAPS_ENABLE_LENGTH 1
#define EEPROM_ADDR_EXT_SENS_ENABLE_START (EEPROM_ADDR_TIMELAPS_ENABLE_START + EEPROM_ADDR_TIMELAPS_ENABLE_LENGTH)
#define EEPROM_ADDR_EXT_SENS_ENABLE_LENGTH 1
#define EEPROM_ADDR_EXT_SENS_UNIT_START (EEPROM_ADDR_EXT_SENS_ENABLE_START + EEPROM_ADDR_EXT_SENS_ENABLE_LENGTH)
#define EEPROM_ADDR_EXT_SENS_UNIT_LENGTH 1
#define EEPROM_SIZE (EEPROM_ADDR_REFRESH_INTERVAL_LENGTH + EEPROM_ADDR_FINGERPRINT_LENGTH + EEPROM_ADDR_TOKEN_LENGTH + \
EEPROM_ADDR_FRAMESIZE_LENGTH + EEPROM_ADDR_BRIGHTNESS_LENGTH + EEPROM_ADDR_CONTRAST_LENGTH + \
@ -306,8 +281,7 @@
EEPROM_ADDR_AEC_VALUE_LENGTH + EEPROM_ADDR_GAIN_CTRL_LENGTH + EEPROM_ADDR_AGC_GAIN_LENGTH + EEPROM_ADDR_LOG_LEVEL_LENGTH + \
EEPROM_ADDR_HOSTNAME_LENGTH + EEPROM_ADDR_SERVICE_AP_ENABLE_LENGTH + EEPROM_ADDR_NETWORK_IP_METHOD_LENGTH +\
EEPROM_ADDR_NETWORK_STATIC_IP_LENGTH + EEPROM_ADDR_NETWORK_STATIC_MASK_LENGTH + EEPROM_ADDR_NETWORK_STATIC_GATEWAY_LENGTH + \
EEPROM_ADDR_NETWORK_STATIC_DNS_LENGTH + EEPROM_ADDR_IMAGE_ROTATION_LENGTH + EEPROM_ADDR_TIMELAPS_ENABLE_LENGTH + \
EEPROM_ADDR_EXT_SENS_ENABLE_LENGTH + EEPROM_ADDR_EXT_SENS_UNIT_LENGTH) ///< how many bits do we need for eeprom memory
EEPROM_ADDR_NETWORK_STATIC_DNS_LENGTH) ///< how many bits do we need for eeprom memory
#endif

View File

@ -18,8 +18,8 @@
*/
MicroSd::MicroSd() {
CardDetected = false;
CardSize = 0;
DetectAfterBoot = false;
sdCardMutex = xSemaphoreCreateMutex();
}
/**
@ -36,73 +36,6 @@ void MicroSd::ReinitCard() {
InitSdCard();
}
/**
* @brief Open file
*
* @param i_file - file
* @param i_path - path and file name
* @return true
* @return false
*/
bool MicroSd::OpenFile(File *i_file, String i_path) {
bool status = false;
if (true == CardDetected) {
#if (true == CONSOLE_VERBOSE_DEBUG)
Serial.println("Opening file: " + i_path);
#endif
if (SD_MMC.cardType() == CARD_NONE) {
Serial.println("No SD card detected");
CardDetected = false;
} else {
*i_file = SD_MMC.open(i_path.c_str(), FILE_APPEND);
if (!*i_file) {
#if (true == CONSOLE_VERBOSE_DEBUG)
Serial.println("Failed to open file");
#endif
CardDetected = false;
} else {
status = true;
#if (true == CONSOLE_VERBOSE_DEBUG)
Serial.println("File opened");
#endif
}
}
}
return status;
}
/**
* @brief Close file
*
* @param i_file - file
*/
void MicroSd::CloseFile(File *i_file) {
if (*i_file) {
i_file->close();
}
}
/**
* @brief Check if file is opened
*
* @param i_file - file
* @return true
* @return false
*/
bool MicroSd::CheckOpenFile(File *i_file) {
if (!*i_file) {
#if (true == CONSOLE_VERBOSE_DEBUG)
Serial.println(F("File not opened!"));
#endif
return false;
} else {
return true;
}
}
/**
@brief Init SD card. And check, if is SD card inserted
@param none
@ -114,13 +47,11 @@ void MicroSd::InitSdCard() {
/* set SD card to 1-line/1-bit mode. GPIO 4 is used for LED and for microSD card. But communication is slower. */
/* https://github.com/espressif/arduino-esp32/blob/master/libraries/SD_MMC/src/SD_MMC.h */
SD_MMC.setPins(SD_PIN_CLK, SD_PIN_CMD, SD_PIN_DATA0);
if (!SD_MMC.begin("/sdcard", true)) {
Serial.println(F("SD Card Mount Failed"));
CardDetected = false;
CardSizeMB = 0;
CardSize = 0;
//DetectAfterBoot = false;
return;
}
@ -129,27 +60,28 @@ void MicroSd::InitSdCard() {
if (cardType == CARD_NONE) {
Serial.println(F("No SD_MMC card attached"));
CardDetected = false;
CardSizeMB = 0;
CardSize = 0;
//DetectAfterBoot = false;
return;
}
/* print card type */
Serial.print(F("Found card. Card Type: "));
if (cardType == CARD_MMC) {
Serial.println(F("MMC"));
Serial.print(F("MMC"));
} else if (cardType == CARD_SD) {
Serial.println(F("SDSC"));
Serial.print(F("SDSC"));
} else if (cardType == CARD_SDHC) {
Serial.println(F("SDHC"));
Serial.print(F("SDHC"));
} else {
Serial.println(F("UNKNOWN"));
Serial.print(F("UNKNOWN"));
}
/* calculation card size */
CardSize = SD_MMC.cardSize() / (1024 * 1024);
Serial.printf(", Card Size: %d MB\n", CardSize);
CardDetected = true;
DetectAfterBoot = true;
/* calculation card size */
CheckCardUsedStatus();
}
/**
@ -192,27 +124,6 @@ void MicroSd::ListDir(fs::FS &fs, String DirName, uint8_t levels) {
}
}
/**
@brief Check directory on the micro SD card
@param fs::FS - card
@param String - dir name
@return bool - status
*/
bool MicroSd::CheckDir(fs::FS &fs, String path) {
bool status = false;
if (true == CardDetected) {
#if (true == CONSOLE_VERBOSE_DEBUG)
Serial.printf("Checking Dir: %s... ", path.c_str());
#endif
if (fs.exists(path.c_str())) {
status = true;
}
}
return status;
}
/**
@brief List directory on the micro SD card
@param fs::FS - card
@ -350,70 +261,6 @@ bool MicroSd::AppendFile(fs::FS &fs, String path, String message) {
return status;
}
/**
@brief Added text to end of file
@param File - file
@param String - message
@return bool - status
*/
bool MicroSd::AppendFile(File *i_file, String *i_msg) {
/* take mutex */
xSemaphoreTake(sdCardMutex, portMAX_DELAY);
bool status = false;
/* check if card is corrupted */
if (false == isCardCorrupted()) {
xSemaphoreGive(sdCardMutex);
return false;
}
/* check if card is detected */
if (true == CardDetected) {
#if (true == CONSOLE_VERBOSE_DEBUG)
Serial.printf("Appending to file:");
#endif
/* check if file is opened */
if (!*i_file) {
Serial.println("File not opened");
CardDetected = false;
} else {
/* write to file */
if (i_file->print(i_msg->c_str())) {
if (*i_file) {
i_file->flush();
/* check if write was OK */
if (!i_file->getWriteError()) {
#if (true == CONSOLE_VERBOSE_DEBUG)
Serial.println("Write OK");
#endif
status = true;
} else {
Serial.println(F("Failed write to file"));
}
} else {
Serial.println(F("File not opened!"));
}
} else {
Serial.println(F("Failed write to file!"));
}
#if (true == CONSOLE_VERBOSE_DEBUG)
Serial.println((status == true) ? "Message appended" : "Append Failed");
#endif
}
}
/* give mutex */
xSemaphoreGive(sdCardMutex);
return status;
}
/**
@brief Rename file on the SD card
@param fs::FS - card
@ -542,185 +389,6 @@ uint16_t MicroSd::FileCount(fs::FS &fs, String DirName, String FileName) {
return FileCount;
}
/**
@brief Remove files in directory
@param fs::FS - card
@param String - dir name
@param int - max files
@return bool - status
*/
bool MicroSd::RemoveFilesInDir(fs::FS &fs, String path, int maxFiles) {
bool ret = false;
File dir = fs.open(path.c_str());
if (!dir) {
return ret;
}
int fileCount = 0;
File file = dir.openNextFile();
while (file) {
ret = true;
String fileName = path + "/" + file.name();
fs.remove(fileName.c_str());
Serial.printf("Removing file: %s\n", fileName.c_str());
fileCount++;
if (fileCount >= maxFiles) {
break;
}
file = dir.openNextFile();
}
return ret;
}
int MicroSd::CountFilesInDir(fs::FS &fs, String path) {
uint16_t file_count = FileCount(fs, path, "");
return file_count;
}
/**
@brief Check card used status
@param none
@return bool - status
*/
void MicroSd::CheckCardUsedStatus() {
CardSizeMB = SD_MMC.cardSize() / (1024 * 1024);
CardTotalMB = SD_MMC.totalBytes() / (1024 * 1024);
CardUsedMB = SD_MMC.usedBytes() / (1024 * 1024);
CardFreeMB = CardSizeMB - CardUsedMB;
FreeSpacePercent = (CardFreeMB * 100) / CardSizeMB;
UsedSpacePercent = 100 - FreeSpacePercent;
#if (true == CONSOLE_VERBOSE_DEBUG)
Serial.printf("Card size: %d MB, Total: %d MB, Used: %d MB, Free: %d GB, Free: %d %% \n", CardSizeMB, CardTotalMB, CardUsedMB, CardFreeMB, FreeSpacePercent);
#endif
}
/**
* @brief Function to check if card is corrupted
*
* @return true
* @return false
*/
bool MicroSd::isCardCorrupted() {
bool ret = true;
if (true == CardDetected) {
#if (true == CONSOLE_VERBOSE_DEBUG)
//Serial.println(F("Checking card..."));
#endif
/* check card size */
uint64_t use = SD_MMC.usedBytes();
uint64_t size = 0;
if (use != 0) {
size = SD_MMC.cardSize();
}
#if (true == CONSOLE_VERBOSE_DEBUG)
Serial.printf("Card size: %llu, Used: %llu\n", size, use);
#endif
/* check space on the card */
if (size == use) {
Serial.println(F("No space left on device!"));
CardDetected = false;
ret = false;
}
/* check another error */
if ((size <= 0 ) || (size == 0) || (use <= 0) || (use == 0)) {
Serial.println(F("No card detected!"));
CardDetected = false;
ret = false;
}
} else {
ret = false;
}
return ret;
}
/**
@brief Write picture to the SD card
@param fs::FS - card
@param String - file name
@return String - data
*/
bool MicroSd::WritePicture(String i_PhotoName, uint8_t *i_PhotoData, size_t i_PhotoLen) {
#if (true == CONSOLE_VERBOSE_DEBUG)
Serial.println(f("WritePicture"));
#endif
bool ret_stat = false;
File file = SD_MMC.open(i_PhotoName, FILE_WRITE);
if (file) {
size_t ret = 0;
ret = file.write(i_PhotoData, i_PhotoLen);
if (ret != i_PhotoLen) {
Serial.println(F("Failed. Error while writing to file"));
} else {
Serial.printf("Saved as %s\n", i_PhotoName.c_str());
ret_stat = true;
}
file.close();
} else {
Serial.printf("Failed. Could not open file: %s\n", i_PhotoName.c_str());
}
return ret_stat;
}
/**
@brief Write picture to the SD card with EXIF data
@param fs::FS - card
@param String - file name
@param uint8_t - data
@param size_t - data length
@param const uint8_t - EXIF data
@param size_t - EXIF data length
@return bool - status
*/
bool MicroSd::WritePicture(String i_PhotoName, uint8_t *i_PhotoData, size_t i_PhotoLen, const uint8_t *i_PtohoExif, size_t i_PhotoExifLen) {
#if (true == CONSOLE_VERBOSE_DEBUG)
Serial.println(F("WritePicture EXIF"));
#endif
bool ret_stat = false;
File file = SD_MMC.open(i_PhotoName, FILE_WRITE);
if (file) {
size_t ret = 0;
ret = file.write(i_PtohoExif, i_PhotoExifLen);
ret += file.write(i_PhotoData, i_PhotoLen);
if (ret != (i_PhotoLen + i_PhotoExifLen)) {
#if (true == CONSOLE_VERBOSE_DEBUG)
Serial.println(F("Failed. Error while writing to file"));
#endif
ret_stat = false;
} else {
#if (true == CONSOLE_VERBOSE_DEBUG)
Serial.printf("Saved as %s\n", i_PhotoName.c_str());
#endif
ret_stat = true;
}
file.close();
} else {
#if (true == CONSOLE_VERBOSE_DEBUG)
Serial.printf("Failed. Could not open file: %s\n", i_PhotoName.c_str());
#endif
ret_stat = false;
}
return ret_stat;
}
/**
@brief Get card detected status
@param none
@ -735,8 +403,8 @@ bool MicroSd::GetCardDetectedStatus() {
@param none
@return uint16_t - size
*/
uint16_t MicroSd::GetCardSizeMB() {
return CardSizeMB;
uint16_t MicroSd::GetCardSize() {
return CardSize;
}
/**
@ -748,49 +416,4 @@ bool MicroSd::GetCardDetectAfterBoot() {
return DetectAfterBoot;
}
/**
@brief Get card total MB
@param none
@return uint16_t - size
*/
uint16_t MicroSd::GetCardTotalMB() {
return CardTotalMB;
}
/**
@brief Get card used MB
@param none
@return uint16_t - size
*/
uint16_t MicroSd::GetCardUsedMB() {
return CardUsedMB;
}
/**
@brief Get card free MB
@param none
@return uint16_t - size
*/
uint16_t MicroSd::GetCardFreeMB() {
return CardFreeMB;
}
/**
@brief Get free space percent
@param none
@return uint8_t - percent
*/
uint8_t MicroSd::GetFreeSpacePercent() {
return FreeSpacePercent;
}
/**
@brief Get used space percent
@param none
@return uint8_t - percent
*/
uint8_t MicroSd::GetUsedSpacePercent() {
return UsedSpacePercent;
}
/* EOF */

View File

@ -21,28 +21,21 @@
D1 4
*/
#pragma once
#ifndef _MICRO_SD_H_
#define _MICRO_SD_H_
#include <Arduino.h>
#include <FS.h>
#include <SD_MMC.h>
#include "Arduino.h"
#include "FS.h"
#include "SD_MMC.h"
#include "mcu_cfg.h"
#include "module_templates.h"
#include "var.h"
class MicroSd {
private:
bool CardDetected; ///< Card detected status
bool DetectAfterBoot; ///< Card detect after boot
uint32_t CardSizeMB; ///< Card size
uint32_t CardTotalMB; ///< Card total size
uint32_t CardUsedMB; ///< Card used size
uint32_t CardFreeMB; ///< Card free size
uint8_t FreeSpacePercent; ///< Free space in percent
uint8_t UsedSpacePercent; ///< Used space in percent
File file; ///< File object
SemaphoreHandle_t sdCardMutex; ///< Mutex for SD card
bool CardDetected; ///< Card detected status
uint16_t CardSize; ///< Card size
bool DetectAfterBoot; ///< Card detect after boot
public:
MicroSd();
@ -50,40 +43,23 @@ public:
void InitSdCard();
void ReinitCard();
bool OpenFile(File*, String);
void CloseFile(File*);
bool CheckOpenFile(File*);
void ListDir(fs::FS &, String, uint8_t);
bool CheckDir(fs::FS &, String);
bool CreateDir(fs::FS &, String);
bool RemoveDir(fs::FS &, String);
void ReadFileConsole(fs::FS &, String);
bool WriteFile(fs::FS &, String, String);
bool AppendFile(fs::FS &, String, String);
bool AppendFile(File*, String*);
bool RenameFile(fs::FS &, String, String);
bool DeleteFile(fs::FS &, String);
uint32_t GetFileSize(fs::FS &, String);
uint16_t FileCount(fs::FS &, String, String);
bool RemoveFilesInDir(fs::FS &, String, int );
int CountFilesInDir(fs::FS &, String );
bool WritePicture(String, uint8_t *, size_t);
bool WritePicture(String, uint8_t *, size_t, const uint8_t *, size_t);
void CheckCardUsedStatus();
bool isCardCorrupted();
bool GetCardDetectedStatus();
uint16_t GetCardSize();
bool GetCardDetectAfterBoot();
uint16_t GetCardSizeMB();
uint16_t GetCardTotalMB();
uint16_t GetCardUsedMB();
uint16_t GetCardFreeMB();
uint32_t GetFreeSpaceMB();
uint8_t GetFreeSpacePercent();
uint8_t GetUsedSpacePercent();
};
#endif
/* EOF */

View File

@ -1,92 +0,0 @@
/**
@file module_AI_Thinker_ESP32-CAM.h
@brief Definition of the AI Thinker ESP32-CAM module
@author Miroslav Pivovarsky
Contact: miroslav.pivovarsky@gmail.com
https://docs.ai-thinker.com/en/esp32-cam
Board configuration in the arduino IDE 2.3.2
Tools -> Board -> ESP32 Arduino -> AI Thinker ESP32
Tools -> CPU Frequency -> 240MHz (WiFi/BT)
Tools -> Core debug level -> None
Tools -> Flash frequency -> 80MHz
Tools -> Flash Mode -> DIO
Tools -> Partition scheme -> Minimal SPIFFS (1.9MB APP with OTA/190KB SPIFFS)
@bug: no know bug
*/
#pragma once
#include "mcu_cfg.h"
#ifdef AI_THINKER_ESP32_CAM
/* --------------- CAMERA CFG -------------------*/
#define PWDN_GPIO_NUM 32 ///< Power down control pin
#define RESET_GPIO_NUM -1 ///< Reset control pin
#define XCLK_GPIO_NUM 0 ///< External clock pin
#define SIOD_GPIO_NUM 26 ///< SCCB: SI/O data pin
#define SIOC_GPIO_NUM 27 ///< SCCB: SI/O control pin
#define Y9_GPIO_NUM 35 ///< SCCB: Y9 pin
#define Y8_GPIO_NUM 34 ///< SCCB: Y8 pin
#define Y7_GPIO_NUM 39 ///< SCCB: Y7 pin
#define Y6_GPIO_NUM 36 ///< SCCB: Y6 pin
#define Y5_GPIO_NUM 21 ///< SCCB: Y5 pin
#define Y4_GPIO_NUM 19 ///< SCCB: Y4 pin
#define Y3_GPIO_NUM 18 ///< SCCB: Y3 pin
#define Y2_GPIO_NUM 5 ///< SCCB: Y2 pin
#define VSYNC_GPIO_NUM 25 ///< Vertical sync pin
#define HREF_GPIO_NUM 23 ///< Line sync pin
#define PCLK_GPIO_NUM 22 ///< Pixel clock pin
/* ------------------ MCU CFG ------------------*/
#define BOARD_NAME F("AI Thinker ESP32-CAM") ///< Board name
#define ENABLE_BROWN_OUT_DETECTION true ///< Enable brown out detection
#define ENABLE_PSRAM true ///< Enable PSRAM
/* --------------- OTA UPDATE CFG --------------*/
#define OTA_UPDATE_FW_FILE PSTR("ESP32_PrusaConnectCam.ino.bin") ///< OTA update firmware file name
#define FW_STATUS_LED_PIN 4 ///< GPIO pin for status FW update LED
#define FW_STATUS_LED_LEVEL_ON HIGH ///< GPIO pin level for status LED ON
/* --------------- FLASH LED CFG ---------------*/
#define ENABLE_CAMERA_FLASH true ///< Enable camera flash function
#define CAMERA_FLASH_DIGITAL_CTRL false ///< Enable camera flash digital control
#define CAMERA_FLASH_PWM_CTRL true ///< Enable camera flash PWM control
#define CAMERA_FLASH_NEOPIXEL false ///< Enable camera flash NeoPixel control
#define FLASH_GPIO_NUM 4 ///< Flash control pin
#define FLASH_NEOPIXEL_LED_PIN -1 ///< External flash control pin. RGB LED NeoPixel
#define FLASH_OFF_STATUS 0 ///< PWM intensity LED for OFF. 0-2^FLASH_PWM_RESOLUTION = 0-255
#define FLASH_ON_STATUS 205 ///< PWM intensity LED for ON. limitation to 80%. 2^FLASH_PWM_RESOLUTION * 0.8% = 204
#define FLASH_PWM_FREQ 2000 ///< frequency of pwm [240MHz / (100 prescale * pwm cycles)] = frequency
#define FLASH_PWM_CHANNEL 0 ///< channel 0
#define FLASH_PWM_RESOLUTION 8 ///< range 1-20bit. 8bit = 0-255 range
/* --------------- SD CARD CFG ---------------*/
#define ENABLE_SD_CARD true ///< Enable SD card function
#define SD_PIN_CLK 14 ///< GPIO pin for SD card clock
#define SD_PIN_CMD 15 ///< GPIO pin for SD card command
#define SD_PIN_DATA0 2 ///< GPIO pin for SD card data 0
/* ---------- RESET CFG CONFIGURATION ----------*/
#define CFG_RESET_PIN 12 ///< GPIO 12 is for reset CFG to default
#define CFG_RESET_LED_PIN 4 ///< GPIO for indication of reset CFG
#define CFG_RESET_LED_LEVEL_ON HIGH ///< GPIO pin level for status LED ON
/* -------------- STATUS LED CFG ----------------*/
#define STATUS_LED_ENABLE true ///< enable/disable status LED
#define STATUS_LED_GPIO_NUM 33 ///< GPIO pin for status LED
#define STATUS_LED_OFF_PIN_LEVEL LOW ///< GPIO pin level for status LED ON
/* -------------- DHT SENSOR CFG ----------------*/
#define DHT_SENSOR_ENABLE true ///< enable/disable DHT sensor
#define DHT_SENSOR_PIN 13 ///< GPIO pin for DHT sensor
#endif // AI_THINKER_ESP32_CAM
/* EOF */

View File

@ -1,101 +0,0 @@
/**
@file module_ESP32-S3-CAM.h
@brief Definition of the diymore esp32-s3-cam module
@author Miroslav Pivovarsky
Contact: miroslav.pivovarsky@gmail.com
Board configuration in the arduino IDE 2.3.2
Tools -> Board -> ESP32 Arduino -> ESP32S3 Dev Module
Tools -> USB CDC on BOOT -> Disable
Tools -> CPU Frequency -> 240MHz (WiFi/BT)
Tools -> Core debug level -> None
Tools -> USB DFU on BOOT -> Disable
Tools -> Erase all Flash Before Sketch Upload -> Disable (first flash, new board = enable. otherwise = disable)
Tools -> Events Run On -> Core 1
Tools -> Flash Mode -> DIO 80MHz
Tools -> Flash Size -> 16MB
Tools -> Jtag Adapter -> Disable
Tools -> Arduino Runs On -> Core 1
Tools -> USB Firmware MSC On Boot -> Disable
Tools -> Partition scheme -> Minimal SPIFFS (1.9MB APP with OTA/190KB SPIFFS)
Tools -> PSRAM -> OPI PSRAM
Tools -> Upload Mode -> UART0 / Hardware CDC
Tools -> Upload Speed -> 921600
Tools -> USB Mode -> Hardware CDC and JTAG
Tools -> Zigbee mode -> Disable
@bug:
*/
#pragma once
#include "mcu_cfg.h"
#ifdef CAMERA_MODEL_ESP32_S3_CAM
/* --------------- CAMERA CFG -------------------*/
#define PWDN_GPIO_NUM -1 ///< Power down control pin
#define RESET_GPIO_NUM -1 ///< Reset control pin
#define XCLK_GPIO_NUM 15 ///< External clock pin
#define SIOD_GPIO_NUM 4 ///< SCCB: SI/O data pin
#define SIOC_GPIO_NUM 5 ///< SCCB: SI/O control pin
#define Y9_GPIO_NUM 16 ///< SCCB: Y9 pin
#define Y8_GPIO_NUM 17 ///< SCCB: Y8 pin
#define Y7_GPIO_NUM 18 ///< SCCB: Y7 pin
#define Y6_GPIO_NUM 12 ///< SCCB: Y6 pin
#define Y5_GPIO_NUM 10 ///< SCCB: Y5 pin
#define Y4_GPIO_NUM 8 ///< SCCB: Y4 pin
#define Y3_GPIO_NUM 9 ///< SCCB: Y3 pin
#define Y2_GPIO_NUM 11 ///< SCCB: Y2 pin
#define VSYNC_GPIO_NUM 6 ///< Vertical sync pin
#define HREF_GPIO_NUM 7 ///< Line sync pin
#define PCLK_GPIO_NUM 13 ///< Pixel clock pin
/* ------------------ MCU CFG ------------------*/
#define BOARD_NAME F("ESP32-S3-CAM") ///< Board name
#define ENABLE_BROWN_OUT_DETECTION false ///< Enable brown out detection
#define ENABLE_PSRAM true ///< Enable PSRAM
/* --------------- OTA UPDATE CFG --------------*/
#define OTA_UPDATE_FW_FILE PSTR("esp32-s3-cam.bin") ///< OTA update firmware file name
#define FW_STATUS_LED_PIN 2 ///< GPIO pin for status FW update LED
#define FW_STATUS_LED_LEVEL_ON HIGH ///< GPIO pin level for status LED ON
/* --------------- FLASH LED CFG ---------------*/
#define ENABLE_CAMERA_FLASH true ///< Enable camera flash function
#define CAMERA_FLASH_DIGITAL_CTRL true ///< Enable camera flash digital control
#define CAMERA_FLASH_PWM_CTRL false ///< Enable camera flash PWM control
#define CAMERA_FLASH_NEOPIXEL true ///< Enable camera flash NeoPixel control
#define FLASH_GPIO_NUM 47 ///< Flash control pin.
#define FLASH_NEOPIXEL_LED_PIN 48 ///< External flash control pin. RGB LED NeoPixel
#define FLASH_OFF_STATUS LOW ///< value for turn off flash
#define FLASH_ON_STATUS HIGH ///< value for turn on flash
//#define FLASH_PWM_FREQ 2000 ///< frequency of pwm [240MHz / (100 prescale * pwm cycles)] = frequency
//#define FLASH_PWM_CHANNEL 0 ///< channel 0
//#define FLASH_PWM_RESOLUTION 8 ///< range 1-20bit. 8bit = 0-255 range
/* --------------- SD CARD CFG ---------------*/
#define ENABLE_SD_CARD true ///< Enable SD card function
#define SD_PIN_CLK 39 ///< GPIO pin for SD card clock
#define SD_PIN_CMD 38 ///< GPIO pin for SD card command
#define SD_PIN_DATA0 40 ///< GPIO pin for SD card data 0
/* ---------- RESET CFG CONFIGURATION ----------*/
#define CFG_RESET_PIN 14 ///< GPIO 16 is for reset CFG to default
#define CFG_RESET_LED_PIN 2 ///< GPIO for indication of reset CFG
#define CFG_RESET_LED_LEVEL_ON HIGH ///< GPIO pin level for status LED ON
/* -------------- STATUS LED CFG ----------------*/
#define STATUS_LED_ENABLE true ///< enable/disable status LED
#define STATUS_LED_GPIO_NUM 2 ///< GPIO pin for status LED
#define STATUS_LED_OFF_PIN_LEVEL HIGH ///< GPIO pin level for status LED ON
/* -------------- DHT SENSOR CFG ----------------*/
#define DHT_SENSOR_ENABLE true ///< enable/disable DHT sensor
#define DHT_SENSOR_PIN 20 ///< GPIO pin for DHT sensor
#endif
/* EOF */

View File

@ -1,103 +0,0 @@
/**
@file module_ESP32-S3-EYE_2_2.h
@brief Definition of the ESP32-S3 EYE 2.2 module
@author Miroslav Pivovarsky
Contact: miroslav.pivovarsky@gmail.com
Board configuration in the arduino IDE 2.3.2
Tools -> Board -> ESP32 Arduino -> ESP32S3 Dev Module
Tools -> USB CDC on BOOT -> Enabled
Tools -> CPU Frequency -> 240MHz (WiFi/BT)
Tools -> Core debug level -> None
Tools -> USB DFU on BOOT -> Disable
Tools -> Erase all Flash Before Sketch Upload -> Disable (first flash, new board = enable. otherwise = disable)
Tools -> Events Run On -> Core 0
Tools -> Flash Mode -> DIO 80MHz
Tools -> Flash Size -> 8MB
Tools -> Jtag Adapter -> Disable
Tools -> Arduino Runs On -> Core 0
Tools -> USB Firmware MSC On Boot -> Disable
Tools -> Partition scheme -> Minimal SPIFFS (1.9MB APP with OTA/190KB SPIFFS)
Tools -> PSRAM -> OPI PSRAM
Tools -> Upload Mode -> USB-OTG CDC (TinyUSB)
Tools -> Upload Speed -> 921600
Tools -> USB Mode -> Hardware CDC and JTAG
Tools -> Zigbee mode -> Disable
https://github.com/espressif/esp-who/blob/master/docs/en/get-started/ESP32-S3-EYE_Getting_Started_Guide.md
@bug: Currently SW don't work with this DEV board
*/
#pragma once
#include "mcu_cfg.h"
#ifdef CAMERA_MODEL_ESP32_S3_EYE_2_2
/* --------------- CAMERA CFG -------------------*/
#define PWDN_GPIO_NUM -1 ///< Power down control pin
#define RESET_GPIO_NUM -1 ///< Reset control pin
#define SIOD_GPIO_NUM 4 ///< SCCB: SI/O data pin
#define SIOC_GPIO_NUM 5 ///< SCCB: SI/O control pin
#define Y2_GPIO_NUM 11 ///< SCCB: Y2 pin
#define Y3_GPIO_NUM 9 ///< SCCB: Y3 pin
#define Y4_GPIO_NUM 8 ///< SCCB: Y4 pin
#define Y5_GPIO_NUM 10 ///< SCCB: Y5 pin
#define Y6_GPIO_NUM 12 ///< SCCB: Y6 pin
#define Y7_GPIO_NUM 18 ///< SCCB: Y7 pin
#define Y8_GPIO_NUM 17 ///< SCCB: Y8 pin
#define Y9_GPIO_NUM 16 ///< SCCB: Y9 pin
#define VSYNC_GPIO_NUM 6 ///< Vertical sync pin
#define HREF_GPIO_NUM 7 ///< Line sync pin
#define PCLK_GPIO_NUM 13 ///< Pixel clock pin
#define XCLK_GPIO_NUM 15 ///< External clock pin
/* ------------------ MCU CFG ------------------*/
#define BOARD_NAME F("ESP32-S3-EYE_2.2") ///< Board name
#define ENABLE_BROWN_OUT_DETECTION false ///< Enable brown out detection
#define ENABLE_PSRAM true ///< Enable PSRAM
/* --------------- OTA UPDATE CFG --------------*/
#define OTA_UPDATE_FW_FILE PSTR("ESP32S3_EYE22.bin") ///< OTA update firmware file name
#define FW_STATUS_LED_PIN 3 ///< GPIO pin for status FW update LED
#define FW_STATUS_LED_LEVEL_ON LOW ///< GPIO pin level for status LED ON
/* --------------- FLASH LED CFG ---------------*/
#define ENABLE_CAMERA_FLASH true ///< Enable camera flash function
#define CAMERA_FLASH_DIGITAL_CTRL true ///< Enable camera flash digital control
#define CAMERA_FLASH_PWM_CTRL false ///< Enable camera flash PWM control
#define CAMERA_FLASH_NEOPIXEL false ///< Enable camera flash NeoPixel control
#define FLASH_GPIO_NUM 48 ///< Flash control pin. This is pin for enable LCD backlight
#define FLASH_NEOPIXEL_LED_PIN -1 ///< External flash control pin. RGB LED NeoPixel
#define FLASH_OFF_STATUS LOW ///< Value for turn off flash
#define FLASH_ON_STATUS HIGH ///< Value for turn on flash
//#define FLASH_PWM_FREQ 2000 ///< frequency of pwm [240MHz / (100 prescale * pwm cycles)] = frequency
//#define FLASH_PWM_CHANNEL 0 ///< channel 0
//#define FLASH_PWM_RESOLUTION 8 ///< range 1-20bit. 8bit = 0-255 range
/* --------------- SD CARD CFG ---------------*/
#define ENABLE_SD_CARD true ///< Enable SD card function
#define SD_PIN_CLK 39 ///< GPIO pin for SD card clock
#define SD_PIN_CMD 38 ///< GPIO pin for SD card command
#define SD_PIN_DATA0 40 ///< GPIO pin for SD card data 0
/* ---------- RESET CFG CONFIGURATION ----------*/
#define CFG_RESET_PIN 1 ///< GPIO 1 is for reset CFG to default. This is button UP+`
#define CFG_RESET_LED_PIN 3 ///< GPIO for indication of reset CFG
#define CFG_RESET_LED_LEVEL_ON LOW ///< GPIO pin level for status LED ON
/* -------------- STATUS LED CFG ----------------*/
#define STATUS_LED_ENABLE true ///< enable/disable status LED
#define STATUS_LED_GPIO_NUM 3 ///< GPIO pin for status LED
#define STATUS_LED_OFF_PIN_LEVEL HIGH ///< GPIO pin level for status LED ON
/* -------------- DHT SENSOR CFG ----------------*/
#define DHT_SENSOR_ENABLE true ///< enable/disable DHT sensor
#define DHT_SENSOR_PIN 46 ///< GPIO pin for DHT sensor
#endif // CAMERA_MODEL_ESP32_S3_EYE_2_2
/* EOF */

View File

@ -1,103 +0,0 @@
/**
@file module_ESP32-S3_Wroom_Freenove.h
@brief Definition of the ESP32-S3 Wroom FreeNove board
@author Miroslav Pivovarsky
Contact: miroslav.pivovarsky@gmail.com
Board configuration in the arduino IDE 2.3.2
Tools -> Board -> ESP32 Arduino -> ESP32S3 Dev Module
Tools -> USB CDC on BOOT -> Disabled
Tools -> CPU Frequency -> 240MHz (WiFi/BT)
Tools -> Core debug level -> None
Tools -> USB DFU on BOOT -> Disable
Tools -> Erase all Flash Before Sketch Upload -> Disable (first flash, new board = enable. otherwise = disable)
Tools -> Events Run On -> Core 0
Tools -> Flash Mode -> QIO 80MHz
Tools -> Flash Size -> 8MB
Tools -> Jtag Adapter -> Disable
Tools -> Arduino Runs On -> Core 0
Tools -> USB Firmware MSC On Boot -> Disable
Tools -> Partition scheme -> Minimal SPIFFS (1.9MB APP with OTA/190KB SPIFFS)
Tools -> PSRAM -> OPI PSRAM
Tools -> Upload Mode -> UART0 / Hardware CDC
Tools -> Upload Speed -> 921600
Tools -> USB Mode -> Hardware CDC and JTAG
Tools -> Zigbee mode -> Disable
https://freenove.com/fnk0085
@bug: no know bug
*/
#pragma once
#include "mcu_cfg.h"
#ifdef ESP32_S3_WROOM_FREENOVE
/* --------------- CAMERA CFG -------------------*/
#define PWDN_GPIO_NUM -1 ///< Power down control pin
#define RESET_GPIO_NUM -1 ///< Reset control pin
#define SIOD_GPIO_NUM 4 ///< SCCB: SI/O data pin
#define SIOC_GPIO_NUM 5 ///< SCCB: SI/O control pin
#define Y2_GPIO_NUM 11 ///< SCCB: Y2 pin
#define Y3_GPIO_NUM 9 ///< SCCB: Y3 pin
#define Y4_GPIO_NUM 8 ///< SCCB: Y4 pin
#define Y5_GPIO_NUM 10 ///< SCCB: Y5 pin
#define Y6_GPIO_NUM 12 ///< SCCB: Y6 pin
#define Y7_GPIO_NUM 18 ///< SCCB: Y7 pin
#define Y8_GPIO_NUM 17 ///< SCCB: Y8 pin
#define Y9_GPIO_NUM 16 ///< SCCB: Y9 pin
#define VSYNC_GPIO_NUM 6 ///< Vertical sync pin
#define HREF_GPIO_NUM 7 ///< Line sync pin
#define PCLK_GPIO_NUM 13 ///< Pixel clock pin
#define XCLK_GPIO_NUM 15 ///< External clock pin
/* ------------------ MCU CFG ------------------*/
#define BOARD_NAME F("ESP32-S3 WROOM Freenove") ///< Board name
#define ENABLE_BROWN_OUT_DETECTION false ///< Enable brown out detection
#define ENABLE_PSRAM true ///< Enable PSRAM
/* --------------- OTA UPDATE CFG --------------*/
#define OTA_UPDATE_FW_FILE PSTR("ESP32-S3-WROOM_FREENOVE.bin") ///< OTA update firmware file name
#define FW_STATUS_LED_PIN 2 ///< GPIO pin for status FW update LED
#define FW_STATUS_LED_LEVEL_ON LOW ///< GPIO pin level for status LED ON
/* --------------- FLASH LED CFG ---------------*/
#define ENABLE_CAMERA_FLASH true ///< Enable camera flash function
#define CAMERA_FLASH_DIGITAL_CTRL true ///< Enable camera flash digital control
#define CAMERA_FLASH_PWM_CTRL false ///< Enable camera flash PWM control
#define CAMERA_FLASH_NEOPIXEL true ///< Enable camera flash NeoPixel control
#define FLASH_GPIO_NUM 14 ///< Flash control pin
#define FLASH_NEOPIXEL_LED_PIN 48 ///< External flash control pin. RGB LED NeoPixel
#define FLASH_OFF_STATUS 0 ///< PWM intensity LED for OFF. 0-2^FLASH_PWM_RESOLUTION = 0-255
#define FLASH_ON_STATUS 205 ///< PWM intensity LED for ON. limitation to 80%. 2^FLASH_PWM_RESOLUTION * 0.8% = 204
#define FLASH_PWM_FREQ 2000 ///< frequency of pwm [240MHz / (100 prescale * pwm cycles)] = frequency
#define FLASH_PWM_CHANNEL 0 ///< channel 0
#define FLASH_PWM_RESOLUTION 8 ///< range 1-20bit. 8bit = 0-255 range
/* --------------- SD CARD CFG ---------------*/
#define ENABLE_SD_CARD true ///< Enable SD card function
#define SD_PIN_CLK 39 ///< GPIO pin for SD card clock
#define SD_PIN_CMD 38 ///< GPIO pin for SD card command
#define SD_PIN_DATA0 40 ///< GPIO pin for SD card data 0
/* ---------- RESET CFG CONFIGURATION ----------*/
#define CFG_RESET_PIN 21 ///< GPIO 12 is for reset CFG to default
#define CFG_RESET_LED_PIN 2 ///< GPIO for indication of reset CFG
#define CFG_RESET_LED_LEVEL_ON HIGH ///< GPIO pin level for status LED ON
/* -------------- STATUS LED CFG ----------------*/
#define STATUS_LED_ENABLE false ///< enable/disable status LED
#define STATUS_LED_GPIO_NUM 2 ///< GPIO pin for status LED
#define STATUS_LED_OFF_PIN_LEVEL LOW ///< GPIO pin level for status LED ON
/* -------------- DHT SENSOR CFG ----------------*/
#define DHT_SENSOR_ENABLE false ///< enable/disable DHT sensor
#define DHT_SENSOR_PIN 47 ///< GPIO pin for DHT sensor
#endif // AI_THINKER_ESP32_CAM
/* EOF */

View File

@ -1,91 +0,0 @@
/**
@file module_ESP32-WROVER-DEV.h
@brief Definition of the ESP32-WROVER-DEV
@author Miroslav Pivovarsky
Contact: miroslav.pivovarsky@gmail.com
https://github.com/Freenove/Freenove_ESP32_WROVER_Board
Board configuration in the arduino IDE 2.3.2
Tools -> Board -> ESP32 Arduino -> ESP32 Wrover Module
Tools -> CPU Frequency -> 240MHz (WiFi/BT)
Tools -> Core debug level -> None
Tools -> Flash frequency -> 80MHz
Tools -> Flash Mode -> DIO
Tools -> Partition scheme -> Minimal SPIFFS (1.9MB APP with OTA/190KB SPIFFS)
@bug: no know bug
*/
#pragma once
#include "mcu_cfg.h"
#ifdef ESP32_WROVER_DEV
/* --------------- CAMERA CFG -------------------*/
#define PWDN_GPIO_NUM -1 ///< Power down control pin
#define RESET_GPIO_NUM -1 ///< Reset control pin
#define XCLK_GPIO_NUM 21 ///< External clock pin
#define SIOD_GPIO_NUM 26 ///< SCCB: SI/O data pin
#define SIOC_GPIO_NUM 27 ///< SCCB: SI/O control pin
#define Y9_GPIO_NUM 35 ///< SCCB: Y9 pin
#define Y8_GPIO_NUM 34 ///< SCCB: Y8 pin
#define Y7_GPIO_NUM 39 ///< SCCB: Y7 pin
#define Y6_GPIO_NUM 36 ///< SCCB: Y6 pin
#define Y5_GPIO_NUM 19 ///< SCCB: Y5 pin
#define Y4_GPIO_NUM 18 ///< SCCB: Y4 pin
#define Y3_GPIO_NUM 5 ///< SCCB: Y3 pin
#define Y2_GPIO_NUM 4 ///< SCCB: Y2 pin
#define VSYNC_GPIO_NUM 25 ///< Vertical sync pin
#define HREF_GPIO_NUM 23 ///< Line sync pin
#define PCLK_GPIO_NUM 22 ///< Pixel clock pin
/* ------------------ MCU CFG ------------------*/
#define BOARD_NAME F("ESP32-WROVER-DEV") ///< Board name
#define ENABLE_BROWN_OUT_DETECTION true ///< Enable brown out detection
#define ENABLE_PSRAM true ///< Enable PSRAM
/* --------------- OTA UPDATE CFG --------------*/
#define OTA_UPDATE_FW_FILE PSTR("ESP32_WROVERDEV.bin") ///< OTA update firmware file name
#define FW_STATUS_LED_PIN 2 ///< GPIO pin for status FW update LED
#define FW_STATUS_LED_LEVEL_ON LOW ///< GPIO pin level for status LED ON
/* --------------- FLASH LED CFG ---------------*/
#define ENABLE_CAMERA_FLASH true ///< Enable camera flash function
#define CAMERA_FLASH_DIGITAL_CTRL true ///< Enable camera flash digital control
#define CAMERA_FLASH_PWM_CTRL false ///< Enable camera flash PWM control
#define CAMERA_FLASH_NEOPIXEL false ///< Enable camera flash NeoPixel control
#define FLASH_GPIO_NUM 14 ///< Flash control pin
#define FLASH_NEOPIXEL_LED_PIN -1 ///< External flash control pin. RGB LED NeoPixel
#define FLASH_OFF_STATUS LOW ///< value for flash OFF
#define FLASH_ON_STATUS HIGH ///< value for flash ON
//#define FLASH_PWM_FREQ 2000 ///< frequency of pwm [240MHz / (100 prescale * pwm cycles)] = frequency
//#define FLASH_PWM_CHANNEL 0 ///< channel 0
//#define FLASH_PWM_RESOLUTION 8 ///< range 1-20bit. 8bit = 0-255 range
/* --------------- SD CARD CFG ---------------*/
#define ENABLE_SD_CARD false ///< Enable SD card function
#define SD_PIN_CLK -1 ///< GPIO pin for SD card clock
#define SD_PIN_CMD -1 ///< GPIO pin for SD card command
#define SD_PIN_DATA0 -1 ///< GPIO pin for SD card data 0
/* ---------- RESET CFG CONFIGURATION ----------*/
#define CFG_RESET_PIN 12 ///< GPIO 12 is for reset CFG to default
#define CFG_RESET_LED_PIN 2 ///< GPIO for indication of reset CFG
#define CFG_RESET_LED_LEVEL_ON LOW ///< GPIO pin level for status LED ON
/* -------------- STATUS LED CFG ----------------*/
#define STATUS_LED_ENABLE true ///< enable/disable status LED
#define STATUS_LED_GPIO_NUM 2 ///< GPIO pin for status LED
#define STATUS_LED_OFF_PIN_LEVEL HIGH ///< GPIO pin level for status LED ON
/* -------------- DHT SENSOR CFG ----------------*/
#define DHT_SENSOR_ENABLE true ///< enable/disable DHT sensor
#define DHT_SENSOR_PIN 46 ///< GPIO pin for DHT sensor
#endif // ESP32_WROVER_DEV
/* EOF */

View File

@ -1,97 +0,0 @@
/**
@file module_ESP32-S3-DEV-CAM.h
@brief Definition of the ESP32-S3 DEV CAM module
@author Miroslav Pivovarsky
Contact: miroslav.pivovarsky@gmail.com
Board configuration in the arduino IDE 2.3.2
Tools -> Board -> ESP32 Arduino -> ESP32S3 Dev Module
Tools -> USB CDC on BOOT -> Enabled
Tools -> CPU Frequency -> 160MHz (WiFi/BT)
Tools -> Core debug level -> None
Tools -> USB DFU on BOOT -> Disable
Tools -> Events Run On -> Core 0
Tools -> Flash Mode -> DIO 80MHz
Tools -> Flash Size -> 16MB
Tools -> Jtag Adapter -> Disable
Tools -> Arduino Runs On -> Core 0
Tools -> USB Firmware MSC On Boot -> Disable
Tools -> Partition scheme -> Minimal SPIFFS (1.9MB APP with OTA/190KB SPIFFS)
Tools -> PSRAM -> OPI PSRAM
Tools -> Upload Mode -> USB-OTG CDC (TinyUSB)
Tools -> Upload Speed -> 921600
Tools -> USB Mode -> Hardware CDC & JTAG
Tools -> Zigbee mode -> Disable
Right USB-C connector is for programming and serial monitor
@bug: Currently SW don't work with this DEV board. WiFi and MicroSD is not working
*/
#pragma once
#include "mcu_cfg.h"
#ifdef CAMERA_MODEL_ESP32_S3_DEV_CAM
/* --------------- CAMERA CFG -------------------*/
#define PWDN_GPIO_NUM -1 ///< Power down control pin
#define RESET_GPIO_NUM -1 ///< Reset control pin
#define XCLK_GPIO_NUM 10 ///< External clock pin
#define SIOD_GPIO_NUM 21 ///< SCCB: SI/O data pin
#define SIOC_GPIO_NUM 14 ///< SCCB: SI/O control pin
#define Y9_GPIO_NUM 11 ///< SCCB: Y9 pin
#define Y8_GPIO_NUM 9 ///< SCCB: Y8 pin
#define Y7_GPIO_NUM 8 ///< SCCB: Y7 pin
#define Y6_GPIO_NUM 6 ///< SCCB: Y6 pin
#define Y5_GPIO_NUM 4 ///< SCCB: Y5 pin
#define Y4_GPIO_NUM 2 ///< SCCB: Y4 pin
#define Y3_GPIO_NUM 3 ///< SCCB: Y3 pin
#define Y2_GPIO_NUM 5 ///< SCCB: Y2 pin
#define VSYNC_GPIO_NUM 13 ///< Vertical sync pin
#define HREF_GPIO_NUM 12 ///< Line sync pin
#define PCLK_GPIO_NUM 7 ///< Pixel clock pin
/* ------------------ MCU CFG ------------------*/
#define BOARD_NAME F("ESP32-S3 DEV CAM") ///< Board name
#define ENABLE_BROWN_OUT_DETECTION false ///< Enable brown out detection
#define ENABLE_PSRAM true ///< Enable PSRAM
/* --------------- OTA UPDATE CFG --------------*/
#define OTA_UPDATE_FW_FILE PSTR("ESP32S3_DEV_CAM.bin") ///< OTA update firmware file name
#define FW_STATUS_LED_PIN 34 ///< GPIO pin for status FW update LED
#define FW_STATUS_LED_LEVEL_ON LOW ///< GPIO pin level for status LED ON
/* --------------- FLASH LED CFG ---------------*/
#define ENABLE_CAMERA_FLASH false ///< Enable camera flash function
#define CAMERA_FLASH_DIGITAL_CTRL false ///< Enable camera flash digital control
#define CAMERA_FLASH_PWM_CTRL false ///< Enable camera flash PWM control
#define CAMERA_FLASH_NEOPIXEL false ///< Enable camera flash NeoPixel control
#define FLASH_GPIO_NUM -1 ///< Flash control pin
#define FLASH_OFF_STATUS 0 ///< PWM intensity LED for OFF. 0-2^FLASH_PWM_RESOLUTION = 0-255
#define FLASH_ON_STATUS 205 ///< PWM intensity LED for ON. limitation to 80%. 2^FLASH_PWM_RESOLUTION * 0.8% = 204
#define FLASH_PWM_FREQ 2000 ///< frequency of pwm [240MHz / (100 prescale * pwm cycles)] = frequency
#define FLASH_PWM_CHANNEL 0 ///< channel 0
#define FLASH_PWM_RESOLUTION 8 ///< range 1-20bit. 8bit = 0-255 range
/* --------------- SD CARD CFG ---------------*/
#define ENABLE_SD_CARD true ///< Enable SD card function
#define SD_PIN_CLK 42 ///< GPIO pin for SD card clock
#define SD_PIN_CMD 39 ///< GPIO pin for SD card command
#define SD_PIN_DATA0 41 ///< GPIO pin for SD card data 0
/* ---------- RESET CFG CONFIGURATION ----------*/
#define CFG_RESET_PIN 2 ///< GPIO 16 is for reset CFG to default
#define CFG_RESET_LED_PIN 34 ///< GPIO for indication of reset CFG
#define CFG_RESET_LED_LEVEL_ON LOW ///< GPIO pin level for status LED ON
/* -------------- STATUS LED CFG ----------------*/
#define STATUS_LED_ENABLE true ///< enable/disable status LED
#define STATUS_LED_GPIO_NUM 34 ///< GPIO pin for status LED
#define STATUS_LED_OFF_PIN_LEVEL LOW ///< GPIO pin level for status LED ON
#endif // CAMERA_MODEL_ESP32_S3_DEV_CAM
/* EOF */

View File

@ -1,106 +0,0 @@
/**
@file module_XIAO_ESP32-S3-cam.h
@brief Definition of the XIAO ESP32-S3 sense cam
@author Miroslav Pivovarsky
Contact: miroslav.pivovarsky@gmail.com
https://www.seeedstudio.com/XIAO-ESP32S3-Sense-p-5639.html
https://wiki.seeedstudio.com/xiao_esp32s3_getting_started/
https://github.com/limengdu/SeeedStudio-XIAO-ESP32S3-Sense-camera
https://github.com/Seeed-Studio/XIAO_Series
Board configuration in the arduino IDE 2.3.2
Tools -> Board -> ESP32 Arduino -> XIAO_ESP32S3
Tools -> USB CDC on BOOT -> Enabled
Tools -> CPU Frequency -> 160MHz (WiFi)
Tools -> Core debug level -> None
Tools -> USB DFU on BOOT -> Disable
Tools -> Erase all Flash Before Sketch Upload -> Disable (first flash, new board = enable. otherwise = disable)
Tools -> Events Run On -> Core 1
Tools -> Flash Mode -> QIO 80MHz
Tools -> Flash Size -> 8MB
Tools -> Jtag Adapter -> Disable
Tools -> Arduino Runs On -> Core 1
Tools -> USB Firmware MSC On Boot -> Disable
Tools -> Partition scheme -> 3MB APP/1.5MB SPIFFS
Tools -> PSRAM -> OPI PSRAM
Tools -> Upload Mode -> UART0 / Hardware CDC
Tools -> Upload Speed -> 921600
Tools -> USB Mode -> Hardware CDC and JTAG
@bug:
*/
#pragma once
#include "mcu_cfg.h"
#ifdef CAMERA_MODEL_XIAO_ESP32_S3_CAM
/* --------------- CAMERA CFG -------------------*/
#define PWDN_GPIO_NUM -1 ///< Power down control pin
#define RESET_GPIO_NUM -1 ///< Reset control pin
#define SIOD_GPIO_NUM 40 ///< SCCB: SI/O data pin
#define SIOC_GPIO_NUM 39 ///< SCCB: SI/O control pin
#define Y2_GPIO_NUM 15 ///< SCCB: Y2 pin
#define Y3_GPIO_NUM 17 ///< SCCB: Y3 pin
#define Y4_GPIO_NUM 18 ///< SCCB: Y4 pin
#define Y5_GPIO_NUM 16 ///< SCCB: Y5 pin
#define Y6_GPIO_NUM 14 ///< SCCB: Y6 pin
#define Y7_GPIO_NUM 12 ///< SCCB: Y7 pin
#define Y8_GPIO_NUM 11 ///< SCCB: Y8 pin
#define Y9_GPIO_NUM 48 ///< SCCB: Y9 pin
#define VSYNC_GPIO_NUM 38 ///< Vertical sync pin
#define HREF_GPIO_NUM 47 ///< Line sync pin
#define PCLK_GPIO_NUM 13 ///< Pixel clock pin
#define XCLK_GPIO_NUM 10 ///< External clock pin
/* ------------------ MCU CFG ------------------*/
#define BOARD_NAME F("XIAO ESP32-S3 Sense cam") ///< Board name
#define ENABLE_BROWN_OUT_DETECTION false ///< Enable brown out detection
#define ENABLE_PSRAM true ///< Enable PSRAM
/* --------------- OTA UPDATE CFG --------------*/
#define OTA_UPDATE_FW_FILE PSTR("XIAO_ESP32S3.bin") ///< OTA update firmware file name
#define FW_STATUS_LED_PIN 21 ///< GPIO pin for status FW update LED
#define FW_STATUS_LED_LEVEL_ON LOW ///< GPIO pin level for status LED ON
/* --------------- FLASH LED CFG ---------------*/
#define ENABLE_CAMERA_FLASH true ///< Enable camera flash function
#define CAMERA_FLASH_DIGITAL_CTRL true ///< Enable camera flash digital control
#define CAMERA_FLASH_PWM_CTRL false ///< Enable camera flash PWM control
#define CAMERA_FLASH_NEOPIXEL false ///< Enable camera flash NeoPixel control
#define FLASH_GPIO_NUM 4 ///< Flash control pin.
#define FLASH_NEOPIXEL_LED_PIN -1 ///< External flash control pin. RGB LED NeoPixel
#define FLASH_OFF_STATUS LOW ///< value for flash OFF
#define FLASH_ON_STATUS HIGH ///< value for flash ON
//#define FLASH_PWM_FREQ 2000 ///< frequency of pwm [240MHz / (100 prescale * pwm cycles)] = frequency
//#define FLASH_PWM_CHANNEL 0 ///< channel 0
//#define FLASH_PWM_RESOLUTION 8 ///< range 1-20bit. 8bit = 0-255 range
/* --------------- SD CARD CFG ---------------*/
#define ENABLE_SD_CARD true ///< Enable SD card function
#define SD_PIN_CLK 7 ///< GPIO pin for SD card clock
#define SD_PIN_CMD 9 ///< GPIO pin for SD card command
#define SD_PIN_DATA0 8 ///< GPIO pin for SD card data 0
/* ---------- RESET CFG CONFIGURATION ----------*/
#define CFG_RESET_PIN 2 ///< GPIO 1 is for reset CFG to default. This is button UP+`
#define CFG_RESET_LED_PIN 21 ///< GPIO for indication of reset CFG
#define CFG_RESET_LED_LEVEL_ON LOW ///< GPIO pin level for status LED ON
/* -------------- STATUS LED CFG ----------------*/
#define STATUS_LED_ENABLE true ///< enable/disable status LED
#define STATUS_LED_GPIO_NUM 21 ///< GPIO pin for status LED
#define STATUS_LED_OFF_PIN_LEVEL LOW ///< GPIO pin level for status LED ON
/* -------------- DHT SENSOR CFG ----------------*/
#define DHT_SENSOR_ENABLE true ///< enable/disable DHT sensor
#define DHT_SENSOR_PIN 1 ///< GPIO pin for DHT sensor
#endif // CAMERA_MODEL_XIAO_ESP32_S3_CAM
/* EOF */

View File

@ -1,47 +0,0 @@
/**
@file module_templates.h
@brief Definition of the module templates
@author Miroslav Pivovarsky
Contact: miroslav.pivovarsky@gmail.com
@bug: no know bug
*/
#pragma once
#include "mcu_cfg.h"
#if ((AI_THINKER_ESP32_CAM + ESP32_WROVER_DEV + CAMERA_MODEL_ESP32_S3_DEV_CAM + CAMERA_MODEL_ESP32_S3_EYE_2_2 + CAMERA_MODEL_XIAO_ESP32_S3_CAM + CAMERA_MODEL_ESP32_S3_CAM + ESP32_S3_WROOM_FREENOVE) != 1)
#error "Exactly one camera model must be defined as true."
#endif
#if (true == AI_THINKER_ESP32_CAM)
#include "module_AI_Thinker_ESP32-CAM.h"
#elif (true == ESP32_WROVER_DEV)
#include "module_ESP32-WROVER-DEV.h"
#elif (true == CAMERA_MODEL_ESP32_S3_DEV_CAM)
#include "module_ESP32_S3_DEV_CAM.h"
#elif (true == CAMERA_MODEL_ESP32_S3_EYE_2_2)
#include "module_ESP32-S3-EYE_2_2.h"
#elif (true == CAMERA_MODEL_XIAO_ESP32_S3_CAM)
#include "module_XIAO_ESP32-S3-cam.h"
#elif (true == CAMERA_MODEL_ESP32_S3_CAM)
#include "module_ESP32-S3-CAM.h"
#elif (true == ESP32_S3_WROOM_FREENOVE)
#include "module_ESP32-S3_Wroom_Freenove.h"
#else
#error "No module selected"
#endif
/* EOF */

View File

@ -75,19 +75,19 @@ String lastTwoChars = command.substring(command.length() - 2);
if (command.startsWith("setwifissid:") && command.endsWith(";")) {
/* remove prefix "setwifissid:" and end of command symbol ";" */
wifi_ssid = command.substring(12, command.length() -1);
log->AddEvent(LogLevel_Info, F("--> Console set WiFi SSID: "), wifi_ssid);
log->AddEvent(LogLevel_Info, "--> Console set WiFi SSID: " + wifi_ssid);
wifim->SetStaSsid(wifi_ssid);
} else if (command.startsWith("setwifipass:") && command.endsWith(";")) {
/* remove prefix "setwifipass:" and end of command symbol ";" */
wifi_pass = command.substring(12, command.length() -1);
log->AddEvent(LogLevel_Info, F("--> Console set WiFi password: "), wifi_pass);
log->AddEvent(LogLevel_Info, "--> Console set WiFi password: " + wifi_pass);
wifim->SetStaPassword(wifi_pass);
} else if (command.startsWith("setauthtoken:") && command.endsWith(";")) {
/* remove prefix "setauthtoken:" and end of command symbol ";" */
auth_token = command.substring(13, command.length() -1);
log->AddEvent(LogLevel_Info, F("--> Console set auth TOKEN for backend: "), auth_token);
log->AddEvent(LogLevel_Info, "--> Console set auth TOKEN for backend: " + auth_token);
connect->SetToken(auth_token);
} else if (command.startsWith("wificonnect") && command.endsWith(";")) {
@ -116,7 +116,7 @@ String lastTwoChars = command.substring(command.length() - 2);
} else if (command.startsWith("resolution:") && command.endsWith(";")) {
uint8_t resolution = command.substring(11, command.length() -1).toInt();
log->AddEvent(LogLevel_Info, F("--> Console set photo resolution: "), String(resolution));
log->AddEvent(LogLevel_Info, "--> Console set photo resolution: " + String(resolution));
if ((resolution >= 0) && (resolution <= 6)) {
cam->SetFrameSize(resolution);
} else {
@ -124,7 +124,7 @@ String lastTwoChars = command.substring(command.length() - 2);
}
} else if (command.startsWith("photoquality:") && command.endsWith(";")) {
uint8_t quality = command.substring(13, command.length() -1).toInt();
log->AddEvent(LogLevel_Info, F("--> Console set photo quality: "), String(quality));
log->AddEvent(LogLevel_Info, "--> Console set photo quality: " + String(quality));
if ((quality >= 10) && (quality <= 63)) {
cam->SetPhotoQuality(quality);
} else {
@ -139,15 +139,7 @@ String lastTwoChars = command.substring(command.length() - 2);
} else if (command.startsWith("setlight") && command.endsWith(";")) {
cam->SetCameraFlashEnable(false);
cam->SetFlashStatus(!cam->GetFlashStatus());
log->AddEvent(LogLevel_Warning, "--> Console set LIGHT: " + String(cam->GetFlashStatus()));
} else if (command.startsWith("loglevel:") && command.endsWith(";")) {
uint8_t level = command.substring(9, command.length() -1).toInt();
log->AddEvent(LogLevel_Info, F("--> Console set log level: "), String(level));
if ((level >= LogLevel_Error) && (level <= LogLevel_Verbose)) {
config->SaveLogLevel((LogLevel_enum) level);
log->SetLogLevel((LogLevel_enum) level);
}
log->AddEvent(LogLevel_Warning, "--> Console set LIGHT: " + String(cam->GetFlashStatus()));
} else if (command.startsWith("mcureboot") && command.endsWith(";")) {
log->AddEvent(LogLevel_Warning, F("--> Reboot MCU!"));
@ -194,7 +186,6 @@ void SerialCfg::PrintAvailableCommands() {
Serial.println(F("photoquality:QUALITY; - set photo quality. 10-63 lower number means higher quality "));
Serial.println(F("setflash; - enable/disable LED flash"));
Serial.println(F("setlight; - enable/disable LED light"));
Serial.println(F("loglevel:LEVEL; - set log level. 0=Error, 1=Warning, 2=Info, 3=Verbose"));
Serial.println(F("mcureboot; - reboot MCU"));
Serial.println(F("commandslist; - print available commands"));
Serial.println(F("-----------------------------------"));

View File

@ -9,9 +9,10 @@
@bug: no know bug
*/
#pragma once
#ifndef _SERIAL_CFG_H
#define _SERIAL_CFG_H
#include <Arduino.h>
#include "Arduino.h"
#include "mcu_cfg.h"
#include "var.h"
@ -47,4 +48,6 @@ public:
extern SerialCfg SystemSerialCfg; ///< SerialCfg object
#endif
/* EOF */

View File

@ -10,7 +10,7 @@
*/
#include "WebServer.h"
#include "server.h"
#include "Certificate.h"
AsyncWebServer server(WEB_SERVER_PORT);
@ -40,40 +40,7 @@ void Server_InitWebServer() {
if (Server_CheckBasicAuth(request) == false)
return;
if (SystemCamera.GetCameraCaptureSuccess() == false) {
request->send(404, "text/plain", "Photo not found!");
return;
}
SystemCamera.SetPhotoSending(true);
SystemLog.AddEvent(LogLevel_Verbose, "Photo size: " + String(SystemCamera.GetPhotoFb()->len) + " bytes");
if (SystemCamera.GetPhotoExifData()->header != NULL) {
/* send photo with exif data */
SystemLog.AddEvent(LogLevel_Verbose, F("Send photo with EXIF data"));
size_t total_len = SystemCamera.GetPhotoExifData()->len + SystemCamera.GetPhotoFb()->len - SystemCamera.GetPhotoExifData()->offset;
auto response = request->beginChunkedResponse("image/jpg", [total_len](uint8_t *buffer, size_t maxLen, size_t index) -> size_t {
size_t len = 0;
if (index < SystemCamera.GetPhotoExifData()->len) {
len = min(maxLen, SystemCamera.GetPhotoExifData()->len - index);
memcpy(buffer, SystemCamera.GetPhotoExifData()->header + index, len);
} else {
size_t offset = index - SystemCamera.GetPhotoExifData()->len + SystemCamera.GetPhotoExifData()->offset;
len = min(maxLen, SystemCamera.GetPhotoFb()->len - offset);
memcpy(buffer, SystemCamera.GetPhotoFb()->buf + offset, len);
}
return len;
});
response->addHeader("Content-Length", String(total_len));
request->send(response);
} else {
/* send photo without exif data */
SystemLog.AddEvent(LogLevel_Verbose, F("Send photo without EXIF data"));
request->send(200, "image/jpg", SystemCamera.GetPhotoFb()->buf, SystemCamera.GetPhotoFb()->len);
}
SystemCamera.SetPhotoSending(false);
request->send_P(200, "image/jpg", SystemCamera.GetPhotoFb()->buf, SystemCamera.GetPhotoFb()->len);
});
/* route to jquery */
@ -111,7 +78,7 @@ void Server_InitWebServer_JsonData() {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: get json_input"));
if (Server_CheckBasicAuth(request) == false)
return;
request->send(200, F("text/plain"), Server_GetJsonData().c_str());
request->send_P(200, F("text/plain"), Server_GetJsonData().c_str());
});
/* route for json with wifi networks */
@ -119,7 +86,7 @@ void Server_InitWebServer_JsonData() {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: get json_wifi"));
if (Server_CheckBasicAuth(request) == false)
return;
request->send(200, F("text/plain"), SystemWifiMngt.GetAvailableWifiNetworks().c_str());
request->send_P(200, F("text/plain"), SystemWifiMngt.GetAvailableWifiNetworks().c_str());
});
/* route for san wi-fi networks */
@ -127,7 +94,7 @@ void Server_InitWebServer_JsonData() {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: scan WI-FI networks"));
if (Server_CheckBasicAuth(request) == false)
return;
request->send(200, F("text/html"), MSG_SCANNING);
request->send_P(200, F("text/html"), MSG_SCANNING);
SystemWifiMngt.ScanWiFiNetwork();
});
@ -159,7 +126,7 @@ void Server_InitWebServer_WebPages() {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: Get index.html"));
if (Server_CheckBasicAuth(request) == false)
return;
Server_handleCacheRequest(request, "text/html", index_html);
});
@ -177,7 +144,7 @@ void Server_InitWebServer_WebPages() {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: Get scripts.js"));
if (Server_CheckBasicAuth(request) == false)
return;
request->send(200, "application/javascript", scripts_js);
request->send_P(200, "application/javascript", scripts_js);
});
@ -186,7 +153,7 @@ void Server_InitWebServer_WebPages() {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: Get page_config.html"));
if (Server_CheckBasicAuth(request) == false)
return;
Server_handleCacheRequest(request, "text/html", page_config_html);
});
@ -195,7 +162,7 @@ void Server_InitWebServer_WebPages() {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: Get page_wifi.html"));
if (Server_CheckBasicAuth(request) == false)
return;
Server_handleCacheRequest(request, "text/html", page_wifi_html);
});
@ -204,7 +171,7 @@ void Server_InitWebServer_WebPages() {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: Get page_auth.html"));
if (Server_CheckBasicAuth(request) == false)
return;
Server_handleCacheRequest(request, "text/html", page_auth_html);
});
@ -213,25 +180,16 @@ void Server_InitWebServer_WebPages() {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: Get page_system.html"));
if (Server_CheckBasicAuth(request) == false)
return;
Server_handleCacheRequest(request, "text/html", page_system_html);
});
/* route for temperature web page */
server.on("/page_temperature.html", HTTP_GET, [](AsyncWebServerRequest* request) {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: Get page_temperature.html"));
if (Server_CheckBasicAuth(request) == false)
return;
Server_handleCacheRequest(request, "text/html", page_temperature_html);
});
/* route to license page */
server.on("/license.html", HTTP_GET, [](AsyncWebServerRequest* request) {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: Get license.html"));
if (Server_CheckBasicAuth(request) == false)
return;
Server_handleCacheRequest(request, "text/html", license_html);
});
@ -240,7 +198,7 @@ void Server_InitWebServer_WebPages() {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: Get gtac.html"));
if (Server_CheckBasicAuth(request) == false)
return;
Server_handleCacheRequest(request, "text/html", gtac_html);
});
@ -249,7 +207,7 @@ void Server_InitWebServer_WebPages() {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: Get privacypolicy.html"));
if (Server_CheckBasicAuth(request) == false)
return;
Server_handleCacheRequest(request, "text/html", privacypolicy_html);
});
@ -258,7 +216,7 @@ void Server_InitWebServer_WebPages() {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: Get cookie.html"));
if (Server_CheckBasicAuth(request) == false)
return;
Server_handleCacheRequest(request, "text/html", cookies_html);
});
@ -270,29 +228,10 @@ void Server_InitWebServer_WebPages() {
if (true == SystemLog.GetCardDetectedStatus()) {
request->send(SD_MMC, SystemLog.GetFilePath() + SystemLog.GetFileName(), "text/plain");
//SystemLog.LogOpenFile();
} else {
request->send(404, "text/plain", "Micro SD card not found with FAT32 partition!");
request->send_P(404, "text/plain", "Micro SD card not found with FAT32 partition!");
}
});
/* route to get temperature */
server.on("/get_temp", HTTP_GET, [](AsyncWebServerRequest* request) {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: Get get_temp"));
if (Server_CheckBasicAuth(request) == false)
return;
request->send(200, "text/plain", String(ExternalTemperatureSensor.GetTemperature()));
});
/* route to get humidity */
server.on("/get_hum", HTTP_GET, [](AsyncWebServerRequest* request) {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: Get get_hum"));
if (Server_CheckBasicAuth(request) == false)
return;
request->send(200, "text/plain", String(ExternalTemperatureSensor.GetHumidity()));
});
}
/**
@ -306,7 +245,7 @@ void Server_InitWebServer_Icons() {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: Get esp32_cam.svg"));
if (Server_CheckBasicAuth(request) == false)
return;
Server_handleCacheRequest(request, "image/svg+xml", esp32_cam_logo_svg);
});
@ -315,7 +254,7 @@ void Server_InitWebServer_Icons() {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: Get github-icon.svg"));
if (Server_CheckBasicAuth(request) == false)
return;
Server_handleCacheRequest(request, "image/svg+xml", github_icon_svg);
});
@ -333,7 +272,7 @@ void Server_InitWebServer_Icons() {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: Get light-icon.svg"));
if (Server_CheckBasicAuth(request) == false)
return;
Server_handleCacheRequest(request, "image/svg+xml", light_icon_off_svg);
});
@ -440,7 +379,7 @@ void Server_InitWebServer_Actions() {
if (Server_CheckBasicAuth(request) == false)
return;
SystemCamera.CapturePhoto();
request->send(200, "text/plain", "Take Photo");
request->send_P(200, "text/plain", "Take Photo");
});
/* route for send photo to prusa backend */
@ -449,7 +388,7 @@ void Server_InitWebServer_Actions() {
if (Server_CheckBasicAuth(request) == false)
return;
Connect.SetSendingIntervalExpired();
request->send(200, "text/plain", "Send Photo");
request->send_P(200, "text/plain", "Send Photo");
});
/* route for change LED status */
@ -461,53 +400,7 @@ void Server_InitWebServer_Actions() {
SystemCamera.SetFlashStatus(!SystemCamera.GetFlashStatus());
SystemCamera.SetCameraFlashEnable(false);
request->send(200, "text/plain", "Change LED status");
});
/* route for change LED status */
server.on("/light", HTTP_GET, [](AsyncWebServerRequest* request) {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: /light set LED status"));
if (Server_CheckBasicAuth(request) == false)
return;
if (request->hasArg("on")) {
SystemLog.AddEvent(LogLevel_Verbose, F("Turning light ON"));
SystemCamera.SetFlashStatus(true);
SystemCamera.SetCameraFlashEnable(false);
request->send(200, "text/plain", "Light ON");
} else if (request->hasArg("off")) {
SystemLog.AddEvent(LogLevel_Verbose, F("Turning light OFF"));
SystemCamera.SetFlashStatus(false);
SystemCamera.SetCameraFlashEnable(false);
request->send(200, "text/plain", "Light OFF");
} else {
request->send(400, "text/plain", "Invalid request");
}
});
/* route for change FLASH status */
server.on("/flash", HTTP_GET, [](AsyncWebServerRequest* request) {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: /flash set flash status"));
if (Server_CheckBasicAuth(request) == false)
return;
if (request->hasArg("on")) {
SystemLog.AddEvent(LogLevel_Verbose, F("Turning flash ON"));
SystemCamera.SetCameraFlashEnable(true);
SystemCamera.SetFlashStatus(false);
request->send(200, "text/plain", "Flash ON");
} else if (request->hasArg("off")) {
SystemLog.AddEvent(LogLevel_Verbose, F("Turning flash OFF"));
SystemCamera.SetCameraFlashEnable(false);
SystemCamera.SetFlashStatus(false);
request->send(200, "text/plain", "Flash OFF");
} else {
request->send(400, "text/plain", "Invalid request");
}
request->send_P(200, "text/plain", "Change LED status");
});
/* reboot MCU */
@ -515,21 +408,10 @@ void Server_InitWebServer_Actions() {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: /action_reboo reboot MCU!"));
if (Server_CheckBasicAuth(request) == false)
return;
request->send(200, F("text/html"), MSG_REBOOT_MCU);
request->send_P(200, F("text/html"), MSG_REBOOT_MCU);
delay(100); /* wait for sending data */
ESP.restart();
});
/* route for change LED status */
server.on("/action_sderase", HTTP_GET, [](AsyncWebServerRequest* request) {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: /action_sderase remove files from SD card"));
if (Server_CheckBasicAuth(request) == false)
return;
StartRemoveSdCard = 1;
request->send(200, F("text/plain"), "Starting remove files from SD card");
});
}
/**
@ -640,14 +522,6 @@ void Server_InitWebServer_Sets() {
response = true;
}
/* set image exif rotation */
if (request->hasParam("image_rotation")) {
SystemLog.AddEvent(LogLevel_Verbose, F("Set image EXIF rotation"));
SystemCamera.SetCameraImageRotation(request->getParam("image_rotation")->value().toInt());
response_msg = MSG_SAVE_OK;
response = true;
}
/* set log level /set_int?log_level=2 */
if (request->hasParam("log_level")) {
SystemLog.AddEvent(LogLevel_Verbose, F("Set log_level"));
@ -672,16 +546,8 @@ void Server_InitWebServer_Sets() {
response = true;
}
/* set saturation */
if (request->hasParam("temp_unit")) {
SystemLog.AddEvent(LogLevel_Verbose, F("Set temp_unit"));
ExternalTemperatureSensor.SetUnit((TemperatureSensorUnit_enum) request->getParam("temp_unit")->value().toInt());
response_msg = MSG_SAVE_OK;
response = true;
}
if (true == response) {
request->send(200, F("text/html"), response_msg.c_str());
request->send_P(200, F("text/html"), response_msg.c_str());
}
});
@ -778,38 +644,14 @@ void Server_InitWebServer_Sets() {
response = true;
}
/* set service AP */
if (request->hasParam("serviceap_enable")) {
SystemLog.AddEvent(LogLevel_Verbose, F("Set service AP enable"));
SystemWifiMngt.SetEnableServiceAp(Server_TransfeStringToBool(request->getParam("serviceap_enable")->value()));
response = true;
}
/* set timelaps enable */
if (request->hasParam("timelaps_enable")) {
SystemLog.AddEvent(LogLevel_Verbose, F("Set timelaps enable"));
#if (ENABLE_SD_CARD == true)
bool val = Server_TransfeStringToBool(request->getParam("timelaps_enable")->value());
if ((true == val) && (SystemLog.GetCardDetectedStatus() == true)) {
Connect.SetTimeLapsPhotoSaveStatus(val);
} else {
Connect.SetTimeLapsPhotoSaveStatus(false);
}
#else
Connect.SetTimeLapsPhotoSaveStatus(false);
#endif
response = true;
}
/* set external temperature sensor enable */
if (request->hasParam("extsens_enable")) {
SystemLog.AddEvent(LogLevel_Verbose, F("Set enable ext temperature"));
ExternalTemperatureSensor.EnableSensor(Server_TransfeStringToBool(request->getParam("extsens_enable")->value()));
response = true;
}
if (true == response) {
request->send(200, F("text/html"), MSG_SAVE_OK);
request->send_P(200, F("text/html"), MSG_SAVE_OK);
}
});
@ -818,19 +660,19 @@ void Server_InitWebServer_Sets() {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: /set_token"));
if (Server_CheckBasicAuth(request) == false)
return;
request->send(200, F("text/html"), MSG_SAVE_OK);
request->send_P(200, F("text/html"), MSG_SAVE_OK);
if (request->hasParam("token")) {
Connect.SetToken(request->getParam("token")->value());
}
});
/* route for set prusa connect hostname /set_hostname?hostname=*/
/* route for set prusa connect hostname */
server.on("/set_hostname", HTTP_GET, [](AsyncWebServerRequest* request) {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: /set_hostname"));
if (Server_CheckBasicAuth(request) == false)
return;
request->send(200, F("text/html"), MSG_SAVE_OK);
request->send_P(200, F("text/html"), MSG_SAVE_OK);
if (request->hasParam("hostname")) {
Connect.SetPrusaConnectHostname(request->getParam("hostname")->value());
@ -856,25 +698,20 @@ void Server_InitWebServer_Sets() {
}
/* check min and max length WI-FI ssid and password */
#if (WIFI_DISABLE_UNENCRYPTED_STA_PASS_CHECK == false)
if (((TmpPassword.length() > 0) && (TmpSsid.length() > 0)) && ((TmpPassword.length() < EEPROM_ADDR_WIFI_PASSWORD_LENGTH) && (TmpSsid.length() < EEPROM_ADDR_WIFI_SSID_LENGTH))) {
#else
if ((TmpSsid.length() > 0) && (TmpSsid.length() < EEPROM_ADDR_WIFI_SSID_LENGTH)) {
#endif
/* send OK response */
request->send(200, F("text/html"), MSG_SAVE_OK_WIFI);
request->send_P(200, F("text/html"), MSG_SAVE_OK_WIFI);
/* save ssid and password */
SystemWifiMngt.SetStaCredentials(TmpSsid, TmpPassword);
SystemWifiMngt.SetStaCredentials(TmpSsid,TmpPassword);
SystemWifiMngt.WiFiStaConnect();
} else {
request->send(200, F("text/html"), MSG_SAVE_NOTOK);
request->send_P(200, F("text/html"), MSG_SAVE_NOTOK);
}
});
/* route for set WI-FI static IP address */
/* route for set WI-FI static IP address */
server.on("/wifi_net_cfg", HTTP_GET, [](AsyncWebServerRequest* request) {
SystemLog.AddEvent(LogLevel_Verbose, F("WEB server: set WI-FI static IP address"));
if (Server_CheckBasicAuth(request) == false)
@ -906,16 +743,18 @@ void Server_InitWebServer_Sets() {
}
/* check min and max length network parameters */
if (((tmpIp.length() > 0) && (tmpMask.length() > 0) && (tmpGw.length() > 0) && (tmpDns.length() > 0)) && ((tmpIp.length() <= IPV4_ADDR_MAX_LENGTH) && (tmpMask.length() <= IPV4_ADDR_MAX_LENGTH) && (tmpGw.length() <= IPV4_ADDR_MAX_LENGTH) && (tmpDns.length() <= IPV4_ADDR_MAX_LENGTH))) {
if (((tmpIp.length() > 0) && (tmpMask.length() > 0) && (tmpGw.length() > 0) && (tmpDns.length() > 0)) &&
((tmpIp.length() <= IPV4_ADDR_MAX_LENGTH) && (tmpMask.length() <= IPV4_ADDR_MAX_LENGTH) &&
(tmpGw.length() <= IPV4_ADDR_MAX_LENGTH) && (tmpDns.length() <= IPV4_ADDR_MAX_LENGTH))) {
/* save ssid and password */
SystemWifiMngt.SetNetworkConfig(tmpIp, tmpMask, tmpGw, tmpDns);
/* send OK response */
request->send(200, F("text/html"), MSG_SAVE_OK_REBOOT);
request->send_P(200, F("text/html"), MSG_SAVE_OK_REBOOT);
} else {
request->send(200, F("text/html"), MSG_SAVE_NOTOK);
request->send_P(200, F("text/html"), MSG_SAVE_NOTOK);
}
});
@ -966,12 +805,12 @@ void Server_InitWebServer_Sets() {
/* send OK response */
if (true == ret) {
request->send(200, F("text/html"), MSG_SAVE_OK);
request->send_P(200, F("text/html"), MSG_SAVE_OK);
} else {
String msg = MSG_SAVE_NOTOK;
msg += " " + ret_msg;
request->send(200, F("text/html"), msg.c_str());
request->send_P(200, F("text/html"), msg.c_str());
}
});
@ -980,7 +819,7 @@ void Server_InitWebServer_Sets() {
SystemLog.AddEvent(LogLevel_Info, F("WEB server: /set_firmware_size"));
if (Server_CheckBasicAuth(request) == false)
return;
request->send(200, F("text/html"), MSG_SAVE_OK);
request->send_P(200, F("text/html"), MSG_SAVE_OK);
/* check cfg for flash */
if (request->hasParam("size")) {
@ -999,12 +838,12 @@ void Server_InitWebServer_Sets() {
if (request->hasParam("mdns")) {
String tmp = request->getParam("mdns")->value();
if (tmp.length() < EEPROM_ADDR_MDNS_RECORD_LENGTH) {
request->send(200, F("text/html"), MSG_SAVE_OK_REBOOT);
request->send_P(200, F("text/html"), MSG_SAVE_OK_REBOOT);
SystemWifiMngt.SetMdns(tmp);
} else {
String msg = "Error save mDNS. Maximum length: " + String(EEPROM_ADDR_MDNS_RECORD_LENGTH);
request->send(200, F("text/html"), msg.c_str());
request->send_P(200, F("text/html"), msg.c_str());
}
}
});
@ -1045,7 +884,7 @@ void Server_InitWebServer_Update() {
[](AsyncWebServerRequest* request, String filename, size_t index, uint8_t* data, size_t len, bool final) {
if (!index) {
FirmwareUpdate.Processing = true;
SystemLog.AddEvent(LogLevel_Info, F("Start FW update from file: "), filename);
SystemLog.AddEvent(LogLevel_Info, "Start FW update from file: " + filename);
FirmwareUpdate.UpdatingStatus = String(SYSTEM_MSG_UPDATE_PROCESS);
if (!Update.begin(UPDATE_SIZE_UNKNOWN, U_FLASH)) {
Update.printError(Serial);
@ -1066,14 +905,15 @@ void Server_InitWebServer_Update() {
SystemLog.AddEvent(LogLevel_Error, String(SYSTEM_MSG_UPDATE_FAIL));
}
}
});
}
);
/* route for start web OTA update from server */
server.on("/web_ota_update", HTTP_GET, [](AsyncWebServerRequest* request) {
SystemLog.AddEvent(LogLevel_Info, F("WEB server: /web_ota_update"));
if (Server_CheckBasicAuth(request) == false)
return;
request->send(200, F("text/html"), MSG_UPDATE_START);
request->send_P(200, F("text/html"), MSG_UPDATE_START);
FirmwareUpdate.Processing = true;
/* check flag */
@ -1094,7 +934,7 @@ void Server_InitWebServer_Update() {
return;
System_CheckNewVersion();
request->send(200, F("text/html"), FirmwareUpdate.CheckNewVersionFwStatus.c_str());
request->send_P(200, F("text/html"), FirmwareUpdate.CheckNewVersionFwStatus.c_str());
});
}
@ -1135,19 +975,7 @@ void Server_resume() {
* @param const char* - data
*/
void Server_handleCacheRequest(AsyncWebServerRequest* request, const char* contentType, const char* data) {
/*
AsyncWebServerResponse* response = request->beginResponse(200, contentType, data);
response->addHeader("Cache-Control", "public, max-age=" + String(WEB_CACHE_INTERVAL));
request->send(response);
*/
AsyncWebServerResponse* response = request->beginChunkedResponse(contentType, [data](uint8_t *buffer, size_t maxLen, size_t index) -> size_t {
const char* dataStart = data + index; // current position in data
size_t dataLeft = strlen(data) - index; // how many bytes are left to send
size_t chunkSize = dataLeft < maxLen ? dataLeft : maxLen; // how many bytes we can send now
memcpy(buffer, dataStart, chunkSize); // copy chunk of data to buffer
return chunkSize; // return chunk size
});
AsyncWebServerResponse *response = request->beginResponse_P(200, contentType, data);
response->addHeader("Cache-Control", "public, max-age=" + String(WEB_CACHE_INTERVAL));
request->send(response);
}
@ -1158,17 +986,17 @@ void Server_handleCacheRequest(AsyncWebServerRequest* request, const char* conte
@return none
*/
void Server_handleNotFound(AsyncWebServerRequest* request) {
String message = F("URL not Found\n\n");
String message = "URL not Found\n\n";
message += "URI: " + request->url() + "\nMethod: ";
message += (request->method() == HTTP_GET) ? F("GET") : F("POST");
message += (request->method() == HTTP_GET) ? "GET" : "POST";
message += "\nArguments: " + String(request->args()) + "\n";
for (uint8_t i = 0; i < request->args(); i++) {
message += " " + request->argName(i) + ": " + request->arg(i) + "\n";
}
request->send(404, F("text/plain"), message);
request->send(404, "text/plain", message);
}
/**
@ -1190,23 +1018,23 @@ String Server_GetJsonData() {
doc_json["brightness"] = String(SystemCamera.GetBrightness());
doc_json["contrast"] = String(SystemCamera.GetContrast());
doc_json["saturation"] = String(SystemCamera.GetSaturation());
doc_json["hmirror"] = Server_TranslateBoolToString(SystemCamera.GetHMirror());
doc_json["vflip"] = Server_TranslateBoolToString(SystemCamera.GetVFlip());
doc_json["lensc"] = Server_TranslateBoolToString(SystemCamera.GetLensC());
doc_json["exposure_ctrl"] = Server_TranslateBoolToString(SystemCamera.GetExposureCtrl());
doc_json["awb"] = Server_TranslateBoolToString(SystemCamera.GetAwb());
doc_json["awb_gain"] = Server_TranslateBoolToString(SystemCamera.GetAwbGain());
doc_json["hmirror"] = (SystemCamera.GetHMirror() == true) ? "true" : "";
doc_json["vflip"] = (SystemCamera.GetVFlip() == true) ? "true" : "";
doc_json["lensc"] = (SystemCamera.GetLensC() == true) ? "true" : "";
doc_json["exposure_ctrl"] = (SystemCamera.GetExposureCtrl() == true) ? "true" : "";
doc_json["awb"] = (SystemCamera.GetAwb() == true) ? "true" : "";
doc_json["awb_gain"] = (SystemCamera.GetAwbGain() == true) ? "true" : "";
doc_json["wb_mode"] = String(SystemCamera.GetAwbMode());
doc_json["bpc"] = Server_TranslateBoolToString(SystemCamera.GetBpc());
doc_json["wpc"] = Server_TranslateBoolToString(SystemCamera.GetWpc());
doc_json["raw_gama"] = Server_TranslateBoolToString(SystemCamera.GetRawGama());
doc_json["aec2"] = Server_TranslateBoolToString(SystemCamera.GetAec2());
doc_json["bpc"] = (SystemCamera.GetBpc() == true) ? "true" : "";
doc_json["wpc"] = (SystemCamera.GetWpc() == true) ? "true" : "";
doc_json["raw_gama"] = (SystemCamera.GetRawGama() == true) ? "true" : "";
doc_json["aec2"] = (SystemCamera.GetAec2() == true) ? "true" : "";
doc_json["ae_level"] = SystemCamera.GetAeLevel();
doc_json["aec_value"] = SystemCamera.GetAecValue();
doc_json["gain_ctrl"] = Server_TranslateBoolToString(SystemCamera.GetGainCtrl());
doc_json["gain_ctrl"] = (SystemCamera.GetGainCtrl() == true) ? "true" : "";
doc_json["agc_gain"] = SystemCamera.GetAgcGaint();
doc_json["led"] = Server_TranslateBoolToString(SystemCamera.GetFlashStatus());
doc_json["flash"] = Server_TranslateBoolToString(SystemCamera.GetCameraFlashEnable());
doc_json["led"] = (SystemCamera.GetFlashStatus() == true) ? "true" : "";
doc_json["flash"] = (SystemCamera.GetCameraFlashEnable() == true) ? "true" : "";
doc_json["flash_time"] = SystemCamera.GetCameraFlashTime();
doc_json["ssid"] = SystemWifiMngt.GetStaSsid();
doc_json["bssid"] = SystemWifiMngt.GetStaBssid();
@ -1217,8 +1045,8 @@ String Server_GetJsonData() {
doc_json["wifi_mode"] = SystemWifiMngt.GetWiFiMode();
doc_json["mdns"] = SystemWifiMngt.GetMdns();
doc_json["service_ap_ssid"] = SystemWifiMngt.GetServiceApSsid();
doc_json["serviceap"] = Server_TranslateBoolToString(SystemWifiMngt.GetEnableServiceAp());
doc_json["auth"] = Server_TranslateBoolToString(WebBasicAuth.EnableAuth);
doc_json["serviceap"] = (SystemWifiMngt.GetEnableServiceAp() == true) ? "true" : "";
doc_json["auth"] = (WebBasicAuth.EnableAuth == true) ? "true" : "";
doc_json["auth_username"] = WebBasicAuth.UserName;
doc_json["last_upload_status"] = Connect.GetBackendReceivedStatus();
doc_json["wifi_network_status"] = SystemWifiMngt.GetStaStatus();
@ -1231,21 +1059,9 @@ String Server_GetJsonData() {
doc_json["net_mask"] = SystemWifiMngt.GetNetStaticMask();
doc_json["net_gw"] = SystemWifiMngt.GetNetStaticGateway();
doc_json["net_dns"] = SystemWifiMngt.GetNetStaticDns();
doc_json["image_rotation"] = SystemCamera.GetCameraImageRotation();
doc_json["timelaps"] = Server_TranslateBoolToString(Connect.GetTimeLapsPhotoSaveStatus());
doc_json["sd_status"] = (SystemLog.GetCardDetectedStatus() == true) ? F("Card detected") : F("No card detected");
doc_json["sd_total"] = SystemLog.GetCardSizeMB();
doc_json["sd_free_p"] = SystemLog.GetFreeSpacePercent();
doc_json["sd_used_p"] = SystemLog.GetUsedSpacePercent();
doc_json["mcu_temp"] = String(McuTemperature.TemperatureCelsius) + " *C";
doc_json["sw_build"] = SW_BUILD;
doc_json["sw_ver"] = SW_VERSION;
doc_json["sw_new_ver"] = FirmwareUpdate.NewVersionFw;
doc_json["extsens_stat"] = ExternalTemperatureSensor.GetSensorStatus();
doc_json["extsen_en"] = ExternalTemperatureSensor.GetUserEnableSensor();
doc_json["ext_temp"] = ExternalTemperatureSensor.GetTemperatureString();
doc_json["ext_hum"] = ExternalTemperatureSensor.GetHumidityString();
doc_json["exttemp_unit"] = ExternalTemperatureSensor.GetTemperatureUnit();
serializeJson(doc_json, string_json);
SystemLog.AddEvent(LogLevel_Verbose, string_json);
@ -1272,8 +1088,8 @@ bool Server_CheckBasicAuth(AsyncWebServerRequest* request) {
@param AsyncWebServerRequest - request
@return void
*/
void Server_streamJpg(AsyncWebServerRequest* request) {
AsyncJpegStreamResponse* response = new AsyncJpegStreamResponse(&SystemCamera, &SystemLog);
void Server_streamJpg(AsyncWebServerRequest *request) {
AsyncJpegStreamResponse *response = new AsyncJpegStreamResponse(&SystemCamera, &SystemLog);
if (!response) {
request->send(501);
return;
@ -1338,15 +1154,4 @@ bool Server_TransfeStringToBool(String data) {
return ret;
}
String Server_TranslateBoolToString(bool i_data) {
String ret = "";
if (true == i_data) {
ret = "true";
} else {
ret = "";
}
return ret;
}
/* EOF */

View File

@ -10,16 +10,21 @@
*/
#pragma once
#ifndef _SERVER_H_
#define _SERVER_H_
#include <Arduino.h>
#include <WiFi.h>
#include <AsyncTCP.h>
#include <ESPAsyncWebServer.h>
#include <AsyncEventSource.h>
#include <AsyncWebSocket.h>
#include <AsyncWebSynchronization.h>
#include <ESPAsyncWebSrv.h>
#include <esp_task_wdt.h>
#include <StringArray.h>
#include <WiFiClientSecure.h>
#include <HTTPClient.h>
#include <EEPROM.h>
#include <Update.h>
#include <ArduinoJson.h>
#include "micro_sd.h"
#include "log.h"
#include "WebPage.h"
#include "WebPage_Icons.h"
#include "mcu_cfg.h"
@ -28,10 +33,10 @@
#include "cfg.h"
#include "jquery.h"
#include "system.h"
#include "log.h"
#include "connect.h"
#include "wifi_mngt.h"
#include "WebStream.h"
#include "ExternalTemperatureSensor.h"
#include "stream.h"
extern AsyncWebServer server; ///< global variable for web server
@ -58,6 +63,6 @@ void Server_streamJpg(AsyncWebServerRequest *);
void Server_GetModuleUptime(String &);
bool Server_TransfeStringToBool(String);
String Server_TranslateBoolToString(bool);
#endif
/* EOF */

View File

@ -10,7 +10,7 @@
@bug: no know bug
*/
#include "WebStream.h"
#include "stream.h"
#define PART_BOUNDARY "123456789000000000000987654321" ///< Must be unique for each stream
static const char *STREAM_CONTENT_TYPE = "multipart/x-mixed-replace;boundary=" PART_BOUNDARY; ///< content type for stream
@ -226,7 +226,7 @@ size_t AsyncJpegStreamResponse::_content(uint8_t *buffer, size_t maxLen, size_t
char buf[50] = { '\0' };
camera->StreamSetFrameSize(_frame.fb->len / 1024);
camera->StreamSetFrameFps(fps);
////sprintf(buf, "Size: %uKB, Time: %ums (%.1f fps)", _frame.fb->len / 1024, fp, fps);
//sprintf(buf, "Size: %uKB, Time: %ums (%.1f fps)", _frame.fb->len / 1024, fp, fps);
sprintf(buf, "Size: %uKB, FPS: %.1f", _frame.fb->len / 1024, fps);
Serial.println(buf);
lastAsyncRequest = end;

View File

@ -11,21 +11,17 @@
@bug: no know bug
*/
#pragma once
#ifndef _STREAM_H_
#define _STREAM_H_
#include <Arduino.h>
#include <WiFi.h>
#include <AsyncTCP.h>
#include <ESPAsyncWebServer.h>
#include "ESPAsyncWebSrv.h"
#include "WebServer.h"
#include "Arduino.h"
#include "mcu_cfg.h"
#include "var.h"
#include "log.h"
#include "camera.h"
class Camera;
typedef struct {
camera_fb_t *fb; ///< pointer to frame buffer
size_t index; ///< index of frame
@ -75,4 +71,5 @@ public:
size_t _content(uint8_t *, size_t , size_t );
};
#endif
/* EOF */

View File

@ -45,7 +45,7 @@ sys_led::sys_led(uint8_t i_pin, uint32_t i_on_duration, Logs *i_log) {
*/
void sys_led::init() {
pinMode(pin, OUTPUT);
digitalWrite(pin, STATUS_LED_OFF_PIN_LEVEL);
digitalWrite(pin, LOW);
}
/**
@ -91,7 +91,7 @@ void sys_led::setTimer(uint32_t i_time) {
uint32_t sys_led::getTimer() {
uint32_t tmp = 0;
if (digitalRead(pin) == STATUS_LED_OFF_PIN_LEVEL) {
if (digitalRead(pin) == LOW) {
tmp = ledOnDuration;
} else {
tmp = time;

View File

@ -9,34 +9,35 @@
@bug: no know bug
*/
#pragma once
#ifndef _SYS_LED_H_
#define _SYS_LED_H_
#include <Arduino.h>
#include "log.h"
#include "mcu_cfg.h"
class Logs;
#include "arduino.h"
class sys_led {
private:
uint8_t pin; ///< pin number for system LED
uint32_t time; ///< speed blinking time system LED
uint32_t ledOnDuration; ///< duration of LED on
Logs *log; ///< pointer to log class
private:
uint8_t pin; ///< pin number for system LED
uint32_t time; ///< speed blinking time system LED
uint32_t ledOnDuration; ///< duration of LED on
Logs *log; ///< pointer to log class
public:
sys_led(uint8_t, uint32_t);
sys_led(uint8_t, uint32_t, Logs *);
~sys_led(){};
public:
sys_led(uint8_t, uint32_t);
sys_led(uint8_t, uint32_t, Logs *);
~sys_led(){};
void init();
void toggle();
void set(bool);
bool get();
void setTimer(uint32_t);
uint32_t getTimer();
void init();
void toggle();
void set(bool);
bool get();
void setTimer(uint32_t);
uint32_t getTimer();
};
extern sys_led system_led;
#endif
/* EOF */

View File

@ -18,9 +18,6 @@
*/
void System_Init() {
SystemLog.AddEvent(LogLevel_Info, F("Init system lib"));
SystemLog.AddEvent(LogLevel_Info, "SW Version: " + String(SW_VERSION) + " Build: " + String(SW_BUILD));
SystemLog.AddEvent(LogLevel_Info, "Board name: " + String(BOARD_NAME));
/* show last reset status */
String reason_simple = System_printMcuResetReasonSimple();
SystemLog.AddEvent(LogLevel_Warning, "CPU reset reason: " + reason_simple);
@ -31,12 +28,10 @@ void System_Init() {
SystemLog.AddEvent(LogLevel_Warning, "CPU1 reset reason: " + reason_core1);
SystemLog.AddEvent(LogLevel_Info, "MCU Temperature: " + String(temperatureRead()) + " *C");
SystemLog.AddEvent(LogLevel_Info, "Internal Total heap: " + String(ESP.getHeapSize()) + " B, Internal Free Heap: " + String(ESP.getFreeHeap()));
SystemLog.AddEvent(LogLevel_Info, "PSRAM Total heap: " + String(ESP.getPsramSize()) + " B, PSRAM Free Heap: " + String(ESP.getFreePsram()));
SystemLog.AddEvent(LogLevel_Info, "Chip model: " + String(ESP.getChipModel()) + ", ChipRevision: " + String(ESP.getChipRevision()) + ", Cpu Freq: " + String(ESP.getCpuFreqMHz()));
SystemLog.AddEvent(LogLevel_Info, "SDK Version: " + String(ESP.getSdkVersion()) + ", Core Version: " + String(ESP.getCoreVersion()));
SystemLog.AddEvent(LogLevel_Info, "Flash Size: " + String(ESP.getFlashChipSize()) + ", Flash Speed " + String(ESP.getFlashChipSpeed()) + ", Flash Mode: " + String(ESP.getFlashChipMode()));
SystemLog.AddEvent(LogLevel_Info, "Internal Total heap: " + String(ESP.getHeapSize()) + " ,internal Free Heap: " + String(ESP.getFreeHeap()));
SystemLog.AddEvent(LogLevel_Info, "SPIRam Total heap: " + String(ESP.getPsramSize()) + " ,SPIRam Free Heap: " + String(ESP.getFreePsram()));
SystemLog.AddEvent(LogLevel_Info, "ChipRevision: " + String(ESP.getChipRevision()) + " ,Cpu Freq: " + String(ESP.getCpuFreqMHz()) + " ,SDK Version: " + String(ESP.getSdkVersion()));
SystemLog.AddEvent(LogLevel_Info, "Flash Size: " + String(ESP.getFlashChipSize()) + " ,Flash Speed " + String(ESP.getFlashChipSpeed()));
System_CheckIfPsramIsUsed();
}
@ -54,11 +49,9 @@ void System_LoadCfg() {
@param none
@return none
*/
bool System_CheckIfPsramIsUsed() {
bool ret = false;
void System_CheckIfPsramIsUsed() {
if (psramFound()) {
SystemLog.AddEvent(LogLevel_Info, F("PSRAM is used."));
ret = true;
void *ptr = malloc(100);
if (ptr != NULL) {
@ -74,8 +67,6 @@ bool System_CheckIfPsramIsUsed() {
} else {
SystemLog.AddEvent(LogLevel_Info, F("PSRAM is not used."));
}
return ret;
}
/**
@ -87,13 +78,12 @@ void System_UpdateInit() {
Update.onProgress([](int progress, size_t total) {
/* update from file */
SystemCamera.SetFlashStatus(true);
digitalWrite(FW_STATUS_LED_PIN, FW_STATUS_LED_LEVEL_ON);
uint8_t updateProgress = (progress * 100) / FirmwareUpdate.FirmwareSize;
SystemLog.AddEvent(LogLevel_Info, "Updating: " + String(FirmwareUpdate.FirmwareSize) + "/" + String(progress) + " -> " + String(updateProgress) + "%");
FirmwareUpdate.PercentProcess = updateProgress;
FirmwareUpdate.TransferedBytes = progress;
delay(10);
digitalWrite(FW_STATUS_LED_PIN, !FW_STATUS_LED_LEVEL_ON);
SystemCamera.SetFlashStatus(false);
});
}
@ -127,14 +117,14 @@ void System_CheckNewVersion() {
WiFiClientSecure client;
client.setCACert(root_CAs_ota);
//client.setInsecure();
FirmwareUpdate.CheckNewVersionFwStatus = F("N/A");
FirmwareUpdate.NewVersionFw = F("Unknown");
FirmwareUpdate.CheckNewVersionFwStatus = "N/A";
FirmwareUpdate.NewVersionFw = "Unknown";
FirmwareUpdate.OtaUpdateFwUrl = "";
FirmwareUpdate.OtaUpdateFwAvailable = false;
/* connect to server and get json */
if (!client.connect(OTA_UPDATE_API_SERVER, 443)) {
FirmwareUpdate.CheckNewVersionFwStatus = F("Failed connect to OTA server!");
if (!client.connect("api.github.com", 443)) {
FirmwareUpdate.CheckNewVersionFwStatus = "Failed connect to OTA server!";
SystemLog.AddEvent(LogLevel_Info, FirmwareUpdate.CheckNewVersionFwStatus);
} else {
@ -191,7 +181,7 @@ void System_CheckNewVersion() {
SystemLog.AddEvent(LogLevel_Info, "Assets[" + String(i) + "]: " + String(name));
/* get FW file and URL */
if (strcmp_P(name, OTA_UPDATE_FW_FILE) == 0) {
if (strcmp(name, OTA_UPDATE_FW_FILE) == 0) {
/* get download URL */
const char* download_url = asset["browser_download_url"];
FirmwareUpdate.OtaUpdateFwUrl = download_url;
@ -262,9 +252,9 @@ bool System_OtaUpdateStart() {
/* mcu configuration */
httpUpdate.rebootOnUpdate(false);
FirmwareUpdate.UpdatingStatus = SYSTEM_MSG_UPDATE_PROCESS;
httpUpdate.setLedPin(FW_STATUS_LED_PIN, FW_STATUS_LED_LEVEL_ON);
httpUpdate.setLedPin(4, HIGH);
SystemLog.AddEvent(LogLevel_Info, F("Start OTA update URL: "), FirmwareUpdate.OtaUpdateFwUrl + ";");
SystemLog.AddEvent(LogLevel_Info, "Start OTA update URL: " + FirmwareUpdate.OtaUpdateFwUrl + ";");
/* start update */
t_httpUpdate_return ret = httpUpdate.update(client, FirmwareUpdate.OtaUpdateFwUrl.c_str());
@ -285,7 +275,7 @@ bool System_OtaUpdateStart() {
break;
}
FirmwareUpdate.Processing = false;
SystemLog.AddEvent(LogLevel_Info, F("OTA update DONE. "), FirmwareUpdate.UpdatingStatus);
SystemLog.AddEvent(LogLevel_Info, "OTA update DONE. " + FirmwareUpdate.UpdatingStatus);
return b_ret;
}
@ -449,18 +439,19 @@ String System_printMcuResetReasonSimple() {
@return none
*/
void System_TaskWifiManagement(void *pvParameters) {
SystemLog.AddEvent(LogLevel_Info, F("Task Wifi Management. core: "), String(xPortGetCoreID()));
SystemLog.AddEvent(LogLevel_Info, "Task Wifi Management. core: " + String(xPortGetCoreID()));
TickType_t xLastWakeTime = xTaskGetTickCount();
while (1) {
/* wifi management. Enable/disable AP_STA mode and STA mode*/
SystemWifiMngt.WifiManagement();
McuTemperature.TemperatureCelsius = temperatureRead();
/* wifi reconnect after signal lost */
SystemWifiMngt.WiFiReconnect();
SystemLog.AddEvent(LogLevel_Verbose, F("WiFiManagement task. Stack free size: "), String(uxTaskGetStackHighWaterMark(NULL)) + "B");
SystemLog.AddEvent(LogLevel_Verbose, F("WiFi status: "), String(WiFi.status()));
SystemLog.AddEvent(LogLevel_Info, "Free RAM: " + String(ESP.getFreeHeap()) + " bytes");
SystemLog.AddEvent(LogLevel_Info, "Free SPIRAM: " + String(ESP.getFreePsram()) + " bytes");
SystemLog.AddEvent(LogLevel_Info, "Temperature: " + String(temperatureRead()) + " *C");
SystemLog.AddEvent(LogLevel_Verbose, "WiFiManagement task. Stack free size: " + String(uxTaskGetStackHighWaterMark(NULL)) + " bytes");
/* reset wdg */
esp_task_wdt_reset();
@ -477,14 +468,14 @@ void System_TaskWifiManagement(void *pvParameters) {
* @return none
*/
void System_TaskMain(void *pvParameters) {
SystemLog.AddEvent(LogLevel_Info, F("System task. core: "), String(xPortGetCoreID()));
SystemLog.AddEvent(LogLevel_Info, "System task. core: " + String(xPortGetCoreID()));
TickType_t xLastWakeTime = xTaskGetTickCount();
while (1) {
/* for ota update */
esp_task_wdt_reset();
System_Main();
SystemLog.AddEvent(LogLevel_Verbose, F("System task. Stack free size: "), String(uxTaskGetStackHighWaterMark(NULL)) + "B");
SystemLog.AddEvent(LogLevel_Verbose, "System task. Stack free size: " + String(uxTaskGetStackHighWaterMark(NULL)) + " bytes");
/* reset wdg */
esp_task_wdt_reset();
@ -501,7 +492,7 @@ void System_TaskMain(void *pvParameters) {
* @return none
*/
void System_TaskCaptureAndSendPhoto(void *pvParameters) {
SystemLog.AddEvent(LogLevel_Info, F("Task photo processing. core: "), String(xPortGetCoreID()));
SystemLog.AddEvent(LogLevel_Info, "Task photo processing. core: " + String(xPortGetCoreID()));
TickType_t xLastWakeTime = xTaskGetTickCount();
while (1) {
@ -509,14 +500,12 @@ void System_TaskCaptureAndSendPhoto(void *pvParameters) {
Connect.SetSendingIntervalCounter(0);
/* send network information to backend */
if ((WL_CONNECTED == WiFi.status()) && (false == FirmwareUpdate.Processing)) {
SystemLog.AddEvent(LogLevel_Verbose, F("Task photo processing. Start sending info"));
esp_task_wdt_reset();
Connect.SendInfoToBackend();
}
/* send photo to backend*/
if ((WL_CONNECTED == WiFi.status()) && (false == FirmwareUpdate.Processing)) {
SystemLog.AddEvent(LogLevel_Verbose, F("Task photo processing. Start sending photo"));
esp_task_wdt_reset();
Connect.TakePictureAndSendToBackend();
}
@ -526,7 +515,7 @@ void System_TaskCaptureAndSendPhoto(void *pvParameters) {
Connect.IncreaseSendingIntervalCounter();
}
SystemLog.AddEvent(LogLevel_Verbose, F("Photo processing task. Stack free size: "), String(uxTaskGetStackHighWaterMark(NULL)) + "B");
SystemLog.AddEvent(LogLevel_Verbose, "Photo processing task. Stack free size: " + String(uxTaskGetStackHighWaterMark(NULL)) + " bytes");
/* reset wdg */
esp_task_wdt_reset();
@ -543,42 +532,17 @@ void System_TaskCaptureAndSendPhoto(void *pvParameters) {
* @return none
*/
void System_TaskSdCardCheck(void *pvParameters) {
SystemLog.AddEvent(LogLevel_Info, F("MicroSdCard check task. core: "), String(xPortGetCoreID()));
SystemLog.AddEvent(LogLevel_Info, "MicroSdCard check task. core: " + String(xPortGetCoreID()));
TickType_t xLastWakeTime = xTaskGetTickCount();
while (1) {
esp_task_wdt_reset();
/* check micro SD card */
if ((true == SystemLog.GetCardDetectAfterBoot()) && (false == SystemLog.GetCardDetectedStatus())) {
SystemLog.LogCloseFile();
SystemLog.ReinitCard();
SystemLog.LogOpenFile();
SystemLog.AddEvent(LogLevel_Warning, F("Reinit micro SD card done!"));
}
/* check card free space */
if (true == SystemLog.GetCardDetectedStatus()) {
SystemLog.AddEvent(LogLevel_Verbose, F("Check card free space"));
SystemLog.CheckCardSpace();
}
/* check maximum log file size */
if (true == SystemLog.GetCardDetectedStatus()) {
SystemLog.AddEvent(LogLevel_Verbose, F("Check maximum log file size"));
SystemLog.CheckMaxLogFileSize();
}
/* check if log file is opened */
if (true == SystemLog.GetCardDetectedStatus()) {
SystemLog.LogCheckOpenedFile();
if (false == SystemLog.GetLogFileOpened()) {
SystemLog.LogOpenFile();
SystemLog.AddEvent(LogLevel_Warning, F("Log file is not opened!"));
}
}
SystemLog.AddEvent(LogLevel_Info, "CardStatus: " + String(SystemLog.GetCardDetectedStatus()) + " FileStatus: " + String(SystemLog.GetLogFileOpened()));
SystemLog.AddEvent(LogLevel_Verbose, F("MicroSdCard task. Stack free size: "), String(uxTaskGetStackHighWaterMark(NULL)) + "B");
SystemLog.AddEvent(LogLevel_Verbose, "MicroSdCard task. Stack free size: " + String(uxTaskGetStackHighWaterMark(NULL)) + " bytes");
/* reset wdg */
esp_task_wdt_reset();
@ -595,13 +559,13 @@ void System_TaskSdCardCheck(void *pvParameters) {
* @return none
*/
void System_TaskSerialCfg(void *pvParameters) {
SystemLog.AddEvent(LogLevel_Info, F("SerialCg task. core: "), String(xPortGetCoreID()));
SystemLog.AddEvent(LogLevel_Info, "SerialCg task. core: " + String(xPortGetCoreID()));
TickType_t xLastWakeTime = xTaskGetTickCount();
while (1) {
esp_task_wdt_reset();
SystemSerialCfg.ProcessIncommingData();
SystemLog.AddEvent(LogLevel_Verbose, F("SerialCfg task. Stack free size: "), String(uxTaskGetStackHighWaterMark(NULL)) + "B");
SystemLog.AddEvent(LogLevel_Verbose, "SerialCfg task. Stack free size: " + String(uxTaskGetStackHighWaterMark(NULL)) + " bytes");
/* reset wdg */
esp_task_wdt_reset();
@ -612,36 +576,30 @@ void System_TaskSerialCfg(void *pvParameters) {
}
/**
* @brief Function for system telemetry task
* @brief Function for stream telemetry task
*
* @param void *pvParameters
* @return none
*/
void System_TaskSystemTelemetry(void *pvParameters) {
SystemLog.AddEvent(LogLevel_Info, F("SystemTelemetry task. core: "), String(xPortGetCoreID()));
void System_TaskStreamTelemetry(void *pvParameters) {
SystemLog.AddEvent(LogLevel_Info, "StreamTelemetry task. core: " + String(xPortGetCoreID()));
TickType_t xLastWakeTime = xTaskGetTickCount();
while (1) {
esp_task_wdt_reset();
SystemLog.AddEvent(LogLevel_Verbose, F("SystemTelemetry task. Stack free size: "), String(uxTaskGetStackHighWaterMark(NULL)) + "B");
SystemLog.AddEvent(LogLevel_Verbose, "StreamTelemetry task. Stack free size: " + String(uxTaskGetStackHighWaterMark(NULL)) + " bytes");
if (SystemCamera.GetStreamStatus()) {
char buf[80] = { '\0' };
sprintf(buf, "Stream, average data in %dsec. FPS: %.1f, Size: %uKB", (TASK_SYSTEM_TELEMETRY / SECOND_TO_MILISECOND), SystemCamera.StreamGetFrameAverageFps(), SystemCamera.StreamGetFrameAverageSize());
sprintf(buf, "Stream, average data in %dsec. FPS: %.1f, Size: %uKB", (TASK_STREAM_TELEMETRY / SECOND_TO_MILISECOND), SystemCamera.StreamGetFrameAverageFps(), SystemCamera.StreamGetFrameAverageSize());
SystemLog.AddEvent(LogLevel_Info, buf);
SystemCamera.StreamClearFrameData();
}
SystemLog.AddEvent(LogLevel_Info, "Free RAM: " + String(ESP.getFreeHeap()) + " B" + ", Min: " + String(ESP.getMinFreeHeap()));
SystemLog.AddEvent(LogLevel_Info, "Free PSRAM: " + String(ESP.getFreePsram()) + " B" + ", Min: " + String(ESP.getMinFreePsram()));
SystemLog.AddEvent(LogLevel_Info, "MCU Temperature: " + String(McuTemperature.TemperatureCelsius) + " *C");
ExternalTemperatureSensor.ReadSensorData();
/* reset wdg */
esp_task_wdt_reset();
/* next start task */
vTaskDelayUntil(&xLastWakeTime, TASK_SYSTEM_TELEMETRY / portTICK_PERIOD_MS);
vTaskDelayUntil(&xLastWakeTime, TASK_STREAM_TELEMETRY / portTICK_PERIOD_MS);
}
}
@ -652,14 +610,14 @@ void System_TaskSystemTelemetry(void *pvParameters) {
* @return none
*/
void System_TaskSysLed(void *pvParameters) {
SystemLog.AddEvent(LogLevel_Info, F("SystemLed task. core: "), String(xPortGetCoreID()));
SystemLog.AddEvent(LogLevel_Info, "SystemLed task. core: " + String(xPortGetCoreID()));
TickType_t xLastWakeTime = xTaskGetTickCount();
while (1) {
system_led.toggle();
/* reset wdg */
esp_task_wdt_reset();
SystemLog.AddEvent(LogLevel_Verbose, F("SystemLed task. Stack free size: "), String(uxTaskGetStackHighWaterMark(NULL)) + "B");
SystemLog.AddEvent(LogLevel_Verbose, "SystemLed task. Stack free size: " + String(uxTaskGetStackHighWaterMark(NULL)) + " bytes");
/* next start task */
vTaskDelayUntil(&xLastWakeTime, system_led.getTimer() / portTICK_PERIOD_MS);
@ -673,13 +631,13 @@ void System_TaskSysLed(void *pvParameters) {
* @return none
*/
void System_TaskWiFiWatchdog(void *pvParameters) {
SystemLog.AddEvent(LogLevel_Info, F("WiFiWatchdog task. core: "), String(xPortGetCoreID()));
SystemLog.AddEvent(LogLevel_Info, "WiFiWatchdog task. core: " + String(xPortGetCoreID()));
TickType_t xLastWakeTime = xTaskGetTickCount();
while (1) {
esp_task_wdt_reset();
SystemWifiMngt.WiFiWatchdog();
SystemLog.AddEvent(LogLevel_Verbose, F("WiFiWatchdog task. Stack free size: "), String(uxTaskGetStackHighWaterMark(NULL)) + "B");
SystemLog.AddEvent(LogLevel_Verbose, "WiFiWatchdog task. Stack free size: " + String(uxTaskGetStackHighWaterMark(NULL)) + " bytes");
/* reset wdg */
esp_task_wdt_reset();
@ -689,44 +647,4 @@ void System_TaskWiFiWatchdog(void *pvParameters) {
}
}
/**
* @brief Function for micro SD card remove files task
*
* @param void *pvParameters
* @return none
*/
void System_TaskSdCardRemove(void *pvParameters) {
SystemLog.AddEvent(LogLevel_Info, F("TaskSdCardRemove. core: "), String(xPortGetCoreID()));
TickType_t xLastWakeTime = xTaskGetTickCount();
SdCardRemoveTime = TASK_SDCARD_FILE_REMOVE;
while (1) {
esp_task_wdt_reset();
if (0 != StartRemoveSdCard) {
if (1 == StartRemoveSdCard) {
SdCardRemoveTime = 5000;
SystemLog.AddEvent(LogLevel_Info, F("Start remove timelaps photo"));
uint16_t file_count = SystemLog.CountFilesInDir(SD_MMC, TIMELAPS_PHOTO_FOLDER);
SystemLog.AddEvent(LogLevel_Info, F("Files in dir: "), String(file_count));
esp_task_wdt_reset();
StartRemoveSdCard = 2;
}
if ( false == SystemLog.RemoveFilesInDir(SD_MMC, TIMELAPS_PHOTO_FOLDER, FILE_REMOVE_MAX_COUNT)) {
SystemLog.AddEvent(LogLevel_Info, F("Remove files in dir done"));
StartRemoveSdCard = 0;
SdCardRemoveTime = TASK_SDCARD_FILE_REMOVE;
}
}
SystemLog.AddEvent(LogLevel_Verbose, F("MicroSdCard task. Stack free size: "), String(uxTaskGetStackHighWaterMark(NULL)) + "B");
/* reset wdg */
esp_task_wdt_reset();
/* next start task */
vTaskDelayUntil(&xLastWakeTime, SdCardRemoveTime / portTICK_PERIOD_MS);
}
}
/* EOF */

View File

@ -9,26 +9,20 @@
@bug: no know bug
*/
#pragma once
#ifndef _SYSTEM_H_
#define _SYSTEM_H_
#include <WiFi.h>
#include <Update.h>
#include <Arduino.h>
#include "Arduino.h"
#include <WiFiClientSecure.h>
#include <HTTPClient.h>
#include <HTTPUpdate.h>
#include <ArduinoJson.h>
#include <esp_wifi.h>
#include "esp32/rom/rtc.h"
#include <esp_task_wdt.h>
#if defined(CONFIG_IDF_TARGET_ESP32)
#include "esp32/rom/rtc.h"
#elif defined(CONFIG_IDF_TARGET_ESP32S3)
#include "esp32s3/rom/rtc.h"
#else
#error "Unsupported chip target"
#endif
#include "mcu_cfg.h"
#include "var.h"
#include "cfg.h"
@ -38,16 +32,15 @@
#include "connect.h"
#include "serial_cfg.h"
#include "sys_led.h"
#include "ExternalTemperatureSensor.h"
#define SYSTEM_MSG_UPDATE_DONE F("FW update successfully done! Please reboot the MCU.")
#define SYSTEM_MSG_UPDATE_FAIL F("FW update failed! Please reboot MCU, and try again.")
#define SYSTEM_MSG_UPDATE_PROCESS F("FW update in progress")
#define SYSTEM_MSG_UPDATE_NO_FW F("No new FW version available!")
#define SYSTEM_MSG_UPDATE_DONE "FW update successfully done! Please reboot the MCU."
#define SYSTEM_MSG_UPDATE_FAIL "FW update failed! Please reboot MCU, and try again."
#define SYSTEM_MSG_UPDATE_PROCESS "FW update in progress"
#define SYSTEM_MSG_UPDATE_NO_FW "No new FW version available!"
void System_Init();
void System_LoadCfg();
bool System_CheckIfPsramIsUsed();
void System_CheckIfPsramIsUsed();
void System_Main();
void System_UpdateInit();
@ -67,9 +60,9 @@ void System_TaskMain(void *);
void System_TaskCaptureAndSendPhoto(void *);
void System_TaskSdCardCheck(void *);
void System_TaskSerialCfg(void *);
void System_TaskSystemTelemetry(void *);
void System_TaskStreamTelemetry(void *);
void System_TaskSysLed(void *);
void System_TaskWiFiWatchdog(void *);
void System_TaskSdCardRemove(void *);
#endif
/* EOF */

View File

@ -13,19 +13,14 @@
WebBasicAuth_struct WebBasicAuth = { false, "", "" };
struct FirmwareUpdate_struct FirmwareUpdate = { "Ready", false, 0, 0, 0, false, false, "", "", "", false };
struct McuTemperature_struct McuTemperature = {0.0};
TaskHandle_t Task_CapturePhotoAndSend;
TaskHandle_t Task_WiFiManagement;
TaskHandle_t Task_SystemMain;
TaskHandle_t Task_SdCardCheck;
TaskHandle_t Task_SerialCfg;
TaskHandle_t Task_SystemTelemetry;
TaskHandle_t Task_StreamTelemetry;
TaskHandle_t Task_SysLed;
TaskHandle_t Task_WiFiWatchdog;
//TaskHandle_t Task_SdCardFileRemove;
uint8_t StartRemoveSdCard = 0;
uint32_t SdCardRemoveTime = 0;
/* EOF */

View File

@ -9,9 +9,10 @@
@bug: no know bug
*/
#pragma once
#ifndef _VARIABLE_H_
#define _VARIABLE_H_
#include <Arduino.h>
#include "Arduino.h"
#include "mcu_cfg.h"
struct WebBasicAuth_struct {
@ -36,25 +37,18 @@ struct FirmwareUpdate_struct {
bool OtaUpdateFwAvailable; ///< flag for available new FW version
};
struct McuTemperature_struct {
float TemperatureCelsius; ///< MCU temperature
};
extern struct WebBasicAuth_struct WebBasicAuth; ///< structure with configuration for basic auth
extern struct FirmwareUpdate_struct FirmwareUpdate; ///< firmware update status and process
extern struct McuTemperature_struct McuTemperature; ///< MCU temperature
extern TaskHandle_t Task_CapturePhotoAndSend; ///< task handle for capture photo and send
extern TaskHandle_t Task_WiFiManagement; ///< task handle for wifi management
extern TaskHandle_t Task_SystemMain; ///< task handle for system main
extern TaskHandle_t Task_SdCardCheck; ///< task handle for sd card check
extern TaskHandle_t Task_SerialCfg; ///< task handle for serial configuration
extern TaskHandle_t Task_SystemTelemetry; ///< task handle for system telemetry
extern TaskHandle_t Task_StreamTelemetry; ///< task handle for stream telemetry
extern TaskHandle_t Task_SysLed; ///< task handle for system led
extern TaskHandle_t Task_WiFiWatchdog; ///< task handle for wifi watchdog
//extern TaskHandle_t Task_SdCardFileRemove; ///< task handle for remove file from sd card
extern uint8_t StartRemoveSdCard;
extern uint32_t SdCardRemoveTime;
#endif
/* EOF */

View File

@ -61,6 +61,7 @@ void WiFiMngt::LoadCfgFromEeprom() {
void WiFiMngt::Init() {
/* check WI-FI mode */
system_led.setTimer(STATUS_LED_WIFI_AP);
log->AddEvent(LogLevel_Info, "WiFi MAC: " + WiFi.macAddress());
/* Set Wi-Fi networks */
SetWifiEvents();
@ -73,14 +74,14 @@ void WiFiMngt::Init() {
ServiceMode = true;
WiFi.softAPConfig(Service_LocalIp, Service_Gateway, Service_Subnet);
WiFi.softAP(SericeApSsid.c_str(), SERVICE_WIFI_PASS, SERVICE_WIFI_CHANNEL);
WiFiMode = F("AP + Client");
WiFiMode = "AP + Client";
log->AddEvent(LogLevel_Info, "Service IP Address: http://" + WiFi.softAPIP().toString());
} else {
log->AddEvent(LogLevel_Warning, F("Service AP mode disabled!"));
WiFi.mode(WIFI_STA);
ServiceMode = false;
WiFiMode = F("Client");
WiFiMode = "Client";
}
/* Set STA IP method. Static or DHCP */
@ -92,7 +93,6 @@ void WiFiMngt::Init() {
} else {
log->AddEvent(LogLevel_Info, F("STA IP Method: DHCP"));
}
log->AddEvent(LogLevel_Info, "WiFi MAC: " + WiFi.macAddress());
esp_wifi_set_ps(WIFI_PS_NONE);
WiFi.setHostname(DEVICE_HOSTNAME);
@ -150,7 +150,7 @@ void WiFiMngt::WifiManagement() {
esp_wifi_set_ps(WIFI_PS_NONE);
WiFiStaConnect();
//WiFi.begin(WifiSsid, WifiPassword);
WiFiMode = F("Client");
WiFiMode = "Client";
#if (WIFI_CLIENT_WAIT_CON == true)
while (WiFi.status() != WL_CONNECTED) {
@ -230,24 +230,12 @@ void WiFiMngt::WiFiStaConnect() {
if (config->CheckActifeWifiCfgFlag() == true) {
system_led.setTimer(STATUS_LED_STA_CONNECTING);
if (false == WiFiStaMultipleNetwork) {
#if (WIFI_DISABLE_UNENCRYPTED_STA_PASS_CHECK == true)
if (WifiPassword == "") {
WiFi.begin(WifiSsid);
log->AddEvent(LogLevel_Info, F("Connecting to STA SSID without password"));
} else {
WiFi.begin(WifiSsid, WifiPassword);
}
#else
WiFi.begin(WifiSsid, WifiPassword);
#endif
log->AddEvent(LogLevel_Info, F("Connecting to STA SSID"));
} else if (true == WiFiStaMultipleNetwork) {
WiFi.begin(WifiSsid, WifiPassword, 0, WiFiStaNetworkBssid);
log->AddEvent(LogLevel_Info, F("Connecting to STA BSSID"));
}
WiFi.setSleep(false);
WiFi.setAutoReconnect(true);
}
}
@ -315,10 +303,8 @@ uint8_t WiFiMngt::ScanWifiNetwork(String ssid) {
WifiScanJson = "";
/* make json with each found WI-FI networks */
if (n <= 0) {
log->AddEvent(LogLevel_Info, "No networks found! [" + String(n) + "]");
ret = 0;
if (n == 0) {
log->AddEvent(LogLevel_Info, F("No networks found!"));
} else {
log->AddEvent(LogLevel_Info, String(n) + " networks found");
log->AddEvent(LogLevel_Info, F("Nr | SSID | RSSI | CH | BSSID | Encryption"));
@ -346,7 +332,7 @@ uint8_t WiFiMngt::ScanWifiNetwork(String ssid) {
// Print SSID and RSSI for each network found
char formattedString[100] = { '\0' };
sprintf(formattedString, "%2d | %-32.32s | %4ld | %2ld | %-17s | %s", i + 1,
sprintf(formattedString, "%2d | %-32.32s | %4d | %2d | %-17s | %s", i + 1,
WiFi.SSID(i).c_str(), WiFi.RSSI(i), WiFi.channel(i), WiFi.BSSIDstr(i).c_str(), TranslateWiFiEncrypion(WiFi.encryptionType(i)).c_str());
log->AddEvent(LogLevel_Info, formattedString);
}
@ -358,7 +344,7 @@ uint8_t WiFiMngt::ScanWifiNetwork(String ssid) {
log->AddEvent(LogLevel_Verbose, WifiScanJson);
/* print status */
if (ret >= 1) {
if (1 <= ret) {
log->AddEvent(LogLevel_Info, "SSID: " + ssid + " found, " + String(ret) + "x");
if (1 < ret) {
memcpy(WiFiStaNetworkBssid, bssid, 6);
@ -367,10 +353,8 @@ uint8_t WiFiMngt::ScanWifiNetwork(String ssid) {
sprintf(mac, "%02X:%02X:%02X:%02X:%02X:%02X", WiFiStaNetworkBssid[0], WiFiStaNetworkBssid[1], WiFiStaNetworkBssid[2], WiFiStaNetworkBssid[3], WiFiStaNetworkBssid[4], WiFiStaNetworkBssid[5]);
log->AddEvent(LogLevel_Info, "WiFi roaming found! Connecting to " + String(mac) + " -> " + String(bestSignal) + "dBm, " + String(WiFiStaMultipleNetwork));
}
} else {
log->AddEvent(LogLevel_Info, "SSID: " + ssid + " not found");
ret = 0;
}
return ret;
@ -420,19 +404,15 @@ void WiFiMngt::WiFiWatchdog() {
/* when is enabled wifi configuration, and is not connected to wifi network, and is available at least one wifi network */
if ((true == config->CheckActifeWifiCfgFlag()) && (WL_CONNECTED != WiFi.status()) && (true == GetFirstConnection())) {
log->AddEvent(LogLevel_Warning, "WiFi WDG. STA connection lost. " + String(StartStaWdg));
log->AddEvent(LogLevel_Warning, F("WiFi WDG. STA connection lost."));
unsigned long currentMillis = millis();
log->AddEvent(LogLevel_Verbose, "Time: " + String(currentMillis - TaskWdg_previousMillis) + "/" + String(WIFI_STA_WDG_TIMEOUT));
if (false == StartStaWdg) {
if (ScanWifiNetwork(WifiSsid) >= 1) {
StartStaWdg = true;
TaskWdg_previousMillis = currentMillis;
log->AddEvent(LogLevel_Warning, F("WiFi STA connection lost. Start watchdog timer!"));
} else {
log->AddEvent(LogLevel_Warning, F("WiFi STA connection lost. No available network!"));
}
StartStaWdg = true;
TaskWdg_previousMillis = currentMillis;
}
if ((true == StartStaWdg) && (currentMillis - TaskWdg_previousMillis >= WIFI_STA_WDG_TIMEOUT)) {
@ -440,12 +420,10 @@ void WiFiMngt::WiFiWatchdog() {
/* restart MCU, or disconnect and connect to WiFi again ? From my point of view, and testing, restart MCU is better */
ESP.restart();
}
} else if (true == StartStaWdg) {
log->AddEvent(LogLevel_Info, F("WiFi WDG. WiFi STA connection OK. Stop watchdog timer!"));
log->AddEvent(LogLevel_Info, F("WiFi STA connection OK. Stop watchdog timer!"));
StartStaWdg = false;
TaskWdg_previousMillis = millis();
}
}
@ -513,15 +491,6 @@ String WiFiMngt::TranslateTxPower(wifi_power_t data) {
case WIFI_POWER_19_5dBm:
ret = F("19.5dBm");
break;
case WIFI_POWER_20dBm:
ret = F("20dBm");
break;
case WIFI_POWER_20_5dBm:
ret = F("20.5dBm");
break;
case WIFI_POWER_21dBm:
ret = F("21dBm");
break;
}
return ret;
@ -825,7 +794,6 @@ void WiFiMngt::SetEnableServiceAp(bool i_data) {
*/
void WiFiMngt::ConnectToSta() {
config->SaveWifiCfgFlag(CFG_WIFI_SETTINGS_SAVED);
WiFiStaConnect();
}
/**

View File

@ -8,14 +8,16 @@
@bug: no know bug
*/
#pragma once
#ifndef _WIFI_MNGT_H_
#define _WIFI_MNGT_H_
#include <WiFi.h>
#include <Arduino.h>
#include "Arduino.h"
#include <esp_task_wdt.h>
#include <ESPmDNS.h>
#include <esp_wifi.h>
#include <esp32-hal-cpu.h>
#include "esp32-hal-cpu.h"
#include "mcu_cfg.h"
#include "var.h"
@ -40,10 +42,6 @@ void WiFiMngt_WiFiEventApStaDisconnected(WiFiEvent_t , WiFiEventInfo_t);
void WiFiMngt_WiFiEventApStaIpAssigned(WiFiEvent_t , WiFiEventInfo_t);
void WiFiMngt_WiFiEventApStaProbeReqRecved(WiFiEvent_t , WiFiEventInfo_t);
/**
* @brief NetworkIpMethod_enum
* method for obtaining IP address
*/
enum NetworkIpMethod_enum {
NetworkIpMethodDhcp = 0, ///< DHCP IP
NetworkIpMethodStatic = 1, ///< STATIC IP
@ -141,4 +139,6 @@ public:
extern WiFiMngt SystemWifiMngt; ///< global variable for wifi management
#endif
/* EOF */

398
README.md
View File

@ -1,75 +1,90 @@
# PrusaConnect ESP32-CAM
This repository includes source code and firmware releases for the **ESP32-cam** module programmed in the **Arduino IDE**. Currently, several versions of boards built on **ESP32/ESP32S3** processors with a camera chip are supported. You can find a list of supported boards below. Additionally, for each supported board, there is a guide on how to upload the firmware, how to compile code for it, some basic information and a list of known issues for this particular board.
This repository includes source code and firmware releases for the ESP32-cam module programmed in the Arduino IDE
This project uses other libraries. It is necessary to install them in the Arduino IDE:
- App [Arduino IDE 2.3.4](https://www.arduino.cc/en/software)
- MCU support [arduino-ESP32 3.1.0](https://github.com/espressif/arduino-esp32)
- ~~Library [ESPAsyncWebSrv 1.2.7](https://github.com/dvarrel/ESPAsyncWebSrv)~~ To version **1.0.3-rc1**
- ~~Library [AsyncTCP 1.1.4](https://github.com/dvarrel/AsyncTCP)~~ To version **1.0.3-rc1**
- Library [AsyncTCP 3.3.1](https://github.com/mathieucarbou/AsyncTCP)
- Library [ESPAsyncWebServer 3.4.5](https://github.com/mathieucarbou/ESPAsyncWebServer)
- Library [ArduinoJson 7.3.0](https://github.com/bblanchon/ArduinoJson)
This project uses other libraries. It is necessary to install them in the Arduino IDE.
- App [Arduino IDE 2.3.2](https://www.arduino.cc/en/software)
- MCU support [ESP32 2.0.16](https://github.com/espressif/arduino-esp32)
- Library [ESPAsyncWebSrv 1.2.7](https://github.com/dvarrel/ESPAsyncWebSrv)
- Library [AsyncTCP 1.1.4](https://github.com/dvarrel/AsyncTCP)
- Library [ArduinoJson 7.0.4](https://github.com/bblanchon/ArduinoJson)
- Library [UniqueID 1.3.0](https://github.com/ricaun/ArduinoUniqueID)
- Library [DHTnew 0.5.2](https://github.com/RobTillaart/DHTNew)
What we need for functionality:
- Supported versions of boards built on **ESP32/ESP32-S3** processors with a camera [here](#supported_boards)
What we need for functionality
- ESP32-CAM AI-thinker board with OV2640 camera module [ here ](#esp32)
- Module board version [here](#different_mcu)
- Install the necessary libraries in the Arduino IDE [ here ](#arduino_lib)
- Arduino IDE configuration [ here ](#arduino_cfg)
- How to flash binary files to ESP32-cam board from Linux/MAC/Windows [ here ](#flash_fw)
- How to flash using Chrome [here](#browser_flash)
- How to compile software in the Arduino IDE [here](#arduino_lib)
- How to connect camera board to Prusa Connect [here](#prusa_connect)
- How to connect ESP32-cam to Prusa Connect [here](#prusa_connect)
- Service AP [here](#service_ap)
- How to reset the configuration to factory settings [here](#factory_cfg)
- Status LED [ here ](#status_led)
- Schematic main board is [here](#schematic)
- Issue with FLASH LED on the main board [here](#led_issue)
- External WiFi antenna [here](#ext_wifi)
- Power supply [here](#power_supply)
- Debug logs [here](#logs)
- Serial console configuration [here](#serial_cfg)
- WEB API [here](#rest)
- Video stream [here](#stream)
- Manual camera focus [here](#man_focus)
- External temperature sensor DHT22/DHT11 [here](#ext_temp)
- Potential issue [here](#issue)
<a name="supported_boards"></a>
## Supported boards
<a name="esp32"></a>
## ESP32-CAM AI-thinker board
It's a few dollars board with **ESP32** MCU and Camera. It's necessary to buy a board with **camera module OV2640**. The board is sold without a programmer by default. It is possible to program it using the FTDI USB to UART converter, or purchase an official programmer for the board. We recommend purchasing an official programmer. It can save a lot of trouble with connecting and programming the board. There are currently [2 different board versions](#different_mcu), but only one is compatible with the official programmer.
| Board name | Support | Stream | Micro SD | FLASH LED | FW update | DHT22/DHT11 | Documentation |
|---------------------------|-------------|--------|----------|-----------|-----------|-------------|---------------------------------------------------|
| Ai-Thinker ESP32-cam | Full | Yes | Yes | Board/Ext | Yes | Yes | [ here ](doc/AI_Thinker-ESP32-cam/README.md) |
| ESP32-S3-EYE 2.2 | Full | Yes | Yes | External | Yes | Yes | [ here ](doc/ESP32-S3-EYE-22/README.md) |
| Freenove ESP32-Wrover cam | Full | Yes | No | External | Yes | Yes | [ here ](doc/ESP32-Wrover-dev/README.md) |
| Freenove ESP32-S3-Wroom | Full | Yes | Yes | Board/Ext | Yes | Yes | [ here ](doc/Freenove%20ESP32-S3-Wroom/README.md) |
| ESP32-S3-DEV-CAM | in Progress | | | External | | | [ here ](doc/ESP32-S3-DEV-CAM/README.md) |
| Seeed Studio XIAO ESP32S3 | Full | Yes | Yes | External | Yes | Yes | [ here ](doc/XIAO_ESP32S3/README.md) |
| ESP32-S3-CAM | Full | Yes | Yes | Board/Ext | Yes | Yes | [ here ](doc/ESP32-S3-CAM/README.md) |
<img src="doc/esp32-cam.jpg" width=30% height=30%>
The compiled firmware for each supported board is published with every release.
In the following picture, we can see the **ESP32-CAM** board and the programator for the board.
<a name="flash_fw"></a>
## How to flash binary files to ESP32-cam board from Linux/MAC/Windows
<img src="doc/esp32_and_prog.jpg" width=30% height=30%>
Uploading a precompiled version of the firmware to the MCU is possible from either Linux or Windows OS. Since different boards use various processors and modules, it is not possible to create a single universal guide. Therefore, it is necessary to select the board you are using and then refer to the documentation on how to upload the firmware to it. Here is list with currently [supported boards](#supported_boards).
It's necessary to use a camera version **OV2640**. If using a different camera, modification of the camera's pinout can be needed, or some camera settings may not work correctly. We recommend to use a camera module with a viewing angle of 120° or 160°.
<a name="browser_flash"></a>
## How to flash using Chrome
It is also possible to flash firmware using ESP Tool on a WEB browser https://espressif.github.io/esptool-js/
These are currently known or tested camera modules:
**This option is currently not supported on the Ai Thinker ESP32-cam board version.**
| Camera chip | FOV | Resolution | Tested | Works | Description |
|-------------|------|------------|--------|-------|------------------------------------------|
| OV2640 | 30° | 2MP | No | N/A | |
| OV2640 | 44° | 2MP | No | N/A | |
| OV2640 | 66° | 2MP | Yes | Yes | Recommended. Standard camera module |
| OV2640 | 120° | 2MP | Yes | Yes | Recommended |
| OV2640 | 160° | 2MP | Yes | Yes | Recommended |
| OV2640 | 200° | 2MP | No | N/A | |
| OV2640 | 222° | 2MP | No | N/A | |
| OV2640IR | 160° | 2MP | Yes | Yes | |
| OV8225N | 66° | 2MP | Yes | Yes | |
| OV3360 | 66° | 3MP | Yes | Yes | |
| OV5640-AF | 72° | 5MP | Yes | Yes | Overheating, slow photo loading |
Ensure that you set the correct baud rate from the documentation for the board you are using (921600). Select the serial port your board is connected to. You can then click "Add File" and select each .bin file for your board. Make sure that you input the **correct Flash Address** from the documentation from your board. For the initial flash, click "Erase Flash", and when that is complete, click "Program." See below for a screenshot of how to configure ESP Tool for the Freenove Wrover board.
<a name="different_mcu"></a>
## Different MCU version
<img src="doc/ESPToolConnect.jpg" width=50% height=50%>
There are currently 2 versions of the board, but only one version is possible programming via oficial **CH340** programmer. The blue rectangle shows the differences between the HW versions.
<img src="doc/ESPTool.png" width=50% height=50%>
<img src="doc/cam_versions.jpg" width=50% height=50%>
<img src="doc/ESPToolFinish.jpg" width=50% height=50%>
The red arrow points to a pin that differs between these boards. In version 1, this pin is used for **MCU RESET (GND/R)**. In version 2, this pin serves as ground **(GND)**. Version 1 can be programmed via **CH340**, whereas version 2 cannot be programmed via **CH340**. For version 2, we tested programming via **FT232RL** or **CP2102**, and the programming process worked successfully.
If we want to program the MCU without the original programmer with **CH340**, or if we want to program the second version of the board, then we need to follow the following instructions. We will need a USB to UART converter, such as **FT232**, **CP2102** or **CH340**. I have tested firmware uploading to the **ESP32-cam** with these converters. Uploading FW to the **second** version using **CH340** did not work for me. Uploading FW using **CH340** only worked for me for the first version of **ESP32-cam** board. For the next steps, I will use the **FT232RL** converter. We connect the **ESP32-cam** to the **FT232** according to the following diagram, where we connect:
<img src="doc/ESP32-cam prog_bb.png" width=60% height=60%>
- **VCC** from **FT232** to **5V** on the **ESP32-CAM**. **CAUTION!** It is necessary to observe the maximum supply voltage of the **ESP32-CAM**, otherwise irreversible damage to the **ESP32-CAM** module may occur.
- **GND** from **FT232** to **GND** on the **ESP32-CAM**
- **TX** from **FT232** to **U0R** on the **ESP32-CAM**
- **RX** from **FT232** to **U0T** on the **ESP32-CAM**
- **IO0** from **ESP32-CAM** to **GND** on **ESP32-CAM**. By connecting the **IO0** pin to **GND**, we switch the board to the mode in which it expects firmware uploading.
Next step is connect the **FT232** converter to the PC and install the correct driver. Then we proceed with uploading the firmware to the **ESP32-cam**, which is described [here](https://github.com/prusa3d/Prusa-Firmware-ESP32-Cam?tab=readme-ov-file#how-to-flash-binary-files-to-esp32-cam-board-from-linuxmacwindows). After successfully uploading the firmware to the **ESP32-cam**, we disconnect **IO0** from **GND**, disconnect the **FT232** converter from the **ESP32-CAM**, and connect the **ESP32-CAM** to the power supply.
The recommended version includes the MCU ESP32 (ESP32-S) with 520 KB of SRAM and external 4M PSRAM
<a name="arduino_lib"></a>
## How to compile software in the Arduino IDE
## Necessary libraries in the Arduino IDE
The software can be compiled and uploaded to the MCU. Software compilation was done in Arduino IDE. To ensure proper functionality, it is necessary to install support for ESP32 boards into Arduino IDE, as well as several other libraries.
Software compilation was done in Arduino IDE 2.3.2. To ensure proper functionality, it is necessary to install support for ESP32 boards into Arduino IDE, as well as several other libraries
As a first step we need to install support for **ESP32 boards**.
At the first step we need to install support for **ESP32 board**.
**File** -> **Preferences** -> **Additional boards managers URLs**
@ -77,134 +92,238 @@ As a first step we need to install support for **ESP32 boards**.
https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json
```
then go to **Tools** -> **Board** -> **Boards Manager...** and install module **ESP32** by **Espressif Systems**.
then go to **Tools** -> **Board** -> **Boards Manager...** and install module **ESP32** by **Espressif Systems**, version **2.0.15**
The next step is to install the necessary libraries. Go to **Sketch** -> **Include Library** -> **Manage Libraries...** or you can use **Ctrl+Shift+I**. Here you can search for the necessary libraries and install them.
The next step is to install the necessary libraries. Go to **Sketch** -> **Include Library** -> **Manage Libraries...** or you can use **Ctrl+Shift+I**. Then you can search for the necessary libraries and install them.
For the installation of the **ESPAsyncWebServer** and **AsyncTCP** libraries, it is necessary to download the **ZIP** archive from the official **GIT** repository, and then import it using **Sketch** -> **Include Library** -> **Add .ZIP Library ...**.
- Library [ESPAsyncWebSrv by dvarrel 1.2.7](https://github.com/dvarrel/ESPAsyncWebSrv)
- Library [AsyncTCP by dvarrel 1.1.4](https://github.com/dvarrel/AsyncTCP)
- Library [ArduinoJson by bblanchon 7.0.4](https://github.com/bblanchon/ArduinoJson)
- Library [UniqueID by Luiz Henrique Cassettari1.3.0](https://github.com/ricaun/ArduinoUniqueID)
You should now be able to build the firmware and upload it to the board. Each board requires a different Arduino IDE configuration. Therefore, it is necessary to select the board from the [supported boards](#supported_boards) and read the documentation on how to build and upload the firmware.
<a name="arduino_cfg"></a>
## Arduino IDE configuration
**For each specific board type, it's necessary** to update the file called **mcu_cfg.h**. Below **line 16** you can find several definitions that specify the version of the board for which the software will be compiled. It is necessary to enable the version of the board that will be used:
Board configuration in the Arduino IDE 2.3.2
- Tools -> Board -> ESP32 Arduino -> AI Thinker ESP32
- Tools -> Flash frequency -> 80MHz
- Tools -> Core Debug Level -> None
- Tools -> Erase all Flash Before Sketch Upload -> Disable **(first flash, new board = enable. otherwise = disable)**
- Tools -> Flash Mode -> DIO
- Tools -> Partition scheme -> Minimal SPIFFS (1.9MB APP with OTA/190KB SPIFFS)
```c
#define AI_THINKER_ESP32_CAM false
#define ESP32_WROVER_DEV true
#define CAMERA_MODEL_ESP32_S3_DEV_CAM false
#define CAMERA_MODEL_ESP32_S3_EYE_2_2 false
#define CAMERA_MODEL_XIAO_ESP32_S3_CAM false
#define CAMERA_MODEL_ESP32_S3_CAM false
When flashing the firmware to a new, empty ESP32-CAM device for the first time, it is necessary to use the 'Erase' function.
This can be found under **Tools** -> **Erase all Flash Before Sketch Upload** -> **Enable**.
After the initial firmware upload to the MCU, it's necessary to disable this option. If you do not disable this option, your camera configuration will continue to be erased from the flash memory after uploading new firmware from the Arduino IDE.
<a name="flash_fw"></a>
## How to flash binary files to ESP32-cam board from Linux/MAC/Windows
#### Linux/MAC
You must use the console to upload the firmware on the MAC or Linux platform. First, ensure you have installed esptool for Python. You can find it on the manufacturer's website, ESPRESSIF, [here](https://docs.espressif.com/projects/esp-at/en/latest/esp32/Get_Started/Downloading_guide.html#linux-or-macos).
And command for FLASH FW is here, where **/dev/ttya0** is your serial interface for communication with the ESP32-cam board. This is the command for the first flash FW to MCU.
```
./esptool -p /dev/ttya0 -b 460800 --before default_reset --after hard_reset --chip esp32 write_flash --erase-all --flash_mode dio --flash_size 4MB --flash_freq 80m 0x1000 ESP32_PrusaConnectCam.ino.bootloader.bin 0x8000 ESP32_PrusaConnectCam.ino.partitions.bin 0x10000 ESP32_PrusaConnectCam.ino.bin
```
<a name="prusa_connect"></a>
## How to connect camera board to Prusa Connect
This command contains the parameter **--eras-all**, which erases the entire flash in the MCU. So, for just updating the firmware, it is necessary to remove the parameter **--eras-all**; otherwise, the MCU configuration will also be deleted. The basic command list can be found [here](https://docs.espressif.com/projects/esptool/en/latest/esp32s3/esptool/basic-commands.html)
- Go to the **Prusa Connect** webpage [https://connect.prusa3D.com](https://connect.prusa3D.com).
- Log in.
Here is the command for updating the firmware in the MCU without erasing the MCU configuration
```
./esptool -p /dev/ttya0 -b 460800 --before default_reset --after hard_reset --chip esp32 write_flash --flash_mode dio --flash_size 4MB --flash_freq 80m 0x1000 ESP32_PrusaConnectCam.ino.bootloader.bin 0x8000 ESP32_PrusaConnectCam.ino.partitions.bin 0x10000 ESP32_PrusaConnectCam.ino.bin
```
Launching the esptool application may be different in different operating systems
#### Windows
Here is the tool and configuration for [windows platform](https://www.espressif.com/en/support/download/other-tools)
You can find the driver for CH340 for Windows for example [here](https://www.wch-ic.com/search?q=CH340&t=downloads) . An older version of the driver is for example [here](https://blog.laskakit.cz/wp-content/uploads/2020/03/CH341SER.zip)
<img src="doc/how to flash chip select.jpg" width=25% height=25%>
It's necessary to erase the FLASH using the **ERASE** button before the first firmware flash.
<img src="doc/how to flash.jpg" width=30% height=30%>
#### Partitions table
Here is the partitions table:
| Name | Type | SubType | Offset | Size | Flags |
|---------|---------|---------|----------|----------|-------|
| nvs | data | nvs | 0x9000 | 0x5000 | |
| otadata | data | ota | 0xe000 | 0x2000 | |
| app0 | app | ota_0 | 0x10000 | 0x1E0000 | |
| app1 | app | ota_1 | 0x1F0000 | 0x1E0000 | |
| spiffs | data | spiffs | 0x3D0000 | 0x20000 | |
| coredump| data | coredump| 0x3F0000 | 0x10000 | |
However, for uploading the firmware, it's important to use this configuration of addresses and files:
- address **0x1000** - **ESP32_PrusaConnectCam.ino.bootloader.bin**
- address **0x8000** - **ESP32_PrusaConnectCam.ino.partitions.bin**
- address **0x10000** - **ESP32_PrusaConnectCam.ino.bin**
<a name="prusa_connect"></a>
## How to connect ESP32-cam to Prusa Connect
- Open up the **Prusa Connect** webpage [connect.prusa3D.com](https://connect.prusa3D.com)
- Log in
- Select a printer you wish to use the camera for.
- Navigate to the **Camera** tab.
- Click **Add new other camera**.
- Click **Add new other camera**
- **A new camera will appear** in the list. Here, you can give the camera a name.
- This is the most important part: Copy the **TOKEN** for the given camera and save it for later use.
<img src="doc/connect_1.jpg" width=50% height=50%>
<img src="doc/connect_2.jpg" width=50% height=50%>
- Connect the Cam to the **USB Power supply**.
- After a brief moment, the camera will start in a **Wi-Fi AP mode**. Essentially, it starts its own Wi-Fi network. The network name (SSID) is **ESP32_camera_UID**, where **UID** is the first three numbers from the **MCU ID**.
- Connect the Cam to the **USB Power supply**
- After a brief moment, the camera will start in a **Wi-Fi AP mode**. Essentially, it starts it's own Wi-Fi network. The network name (SSID) is **ESP32_camera_UID**, where **UID** is the first three numbers from the **MCU ID**.
- Find the camera in the Wi-Fi list on your computer.
- Enter the default password: **12345678** and connect to it. After establishing a successful connection, your computer might complain about having "No Internet" on the given network. That is OK.
- Open up a new web browser.
- Enter [http://192.168.0.1](http://192.168.0.1) as the URL. Alternatively, you can also try to use the http://prusa-esp32cam.local hostname (mDNS) instead of the IP address.
- Open up the **192.168.0.1** IP Address as a webpage. Alternatively, you can also use the http://prusa-esp32cam.local hostname (mDNS) instead of the IP Address.
- The camera's configuration interface should appear.
- In the **Wi-Fi configuration tab** it's necessary to set the SSID of the WiFi network and the password of the WiFi network to which the camera should connect in order to be able to upload images to Prusa Connect. Make sure to click the **Save & Connect** button when you're done.
- In the **Wi-Fi configuration tab** It's necessary to set the SSID of the WiFi network and the password of the WiFi network to which the camera should connect in order to be able to upload images to Prusa Connect. And click to **Save & Connect** button
<img src="doc/connect_4.jpg" width=50% height=50%>
- In the **Camera configuration tab**, insert the **Token** you have obtained earlier into the marked field. Click **Save**. Wait until the token has been saved successfully.
- In the **Camera configuration tab**, insert the **Token** into the marked field. Click **Save**. **This is the Prusa Connect camera token we have obtained in an earlier step.** Wait until the token has been save successfully.
<img src="doc/connect_3.jpg" width=50% height=50%>
In this same tab you should also configure a few image settings:
- Since we're in the camera configuration tab already, we can set up the image options:
- Set up the **resolution**. This will improve the image quality significantly, as the resolution is set to the lowest possible by default.
- Set up the **Trigger interval** and click **Save**.
- Clicking **Refresh snapshot** will refresh the image you see on the page.
- We should now have completed setting up the camera.
While we are on the ESP camera's configuration page, let's take a quick look at the other options it offers:
- Camera configuration tab contains
While we are on the ESP camera's configuration page, let's take a quick look at the other options it offers.
- Camera configuration tab contain
- Camera cip settings
- Authentication token setting
- Camera flash settings
- Wi-Fi configuration tab contains
- Wi-Fi configuration tab contain
- Setting the wifi network to which the camera can connect
- The possibility of turning off the service AP
- Option to set static IP addresses for WiFi networks to which the camera connects
- On the **Authentication** tab, you can set a password to access the configuration page. Default login is admin:admin.
- On the **Authentication** tab, you can set a password to access the configuration page.
- The **System tab** provides several advanced options such as:
- Setting a Hostname (mDNS record) for easier future access to the configuration page over the local network.
- For a manual firmware update, select the firmware file **ESP32_PrusaConnectCam.ino.bin** and click **Upload file & Update**. Afterwards, reboot the camera.
- Update from cloud. To check for firmware updates, select **Check Update from cloud**. If a newer version is available, click **Update from cloud**. Note that the camera has to be connected to the Internet, before using these functions.
- Setting **log level** and getting logs from the camera. To get the logs, it is necessary to have a micro SD card formatted to **FAT32** inserted in the camera!
- Check the status of uploading the image to Prusa Connect using the **PrusaConnect Status:** variable.
**Interesting improvements.** There is a protective film on the camera module. The protective film needs to be removed from the lens.
<img src="doc/cam_prot_film.jpg" width=50% height=50%>
The second problem is that the camera module is not usually attached to the micro SD card slot. Therefore, the camera module overheats. This can permanently damage the camera module. If the quality of the camera module decreases, the resulting image starts to have a purple tint. Therefore, it is necessary to attach the camera module to the micro SD card socket with double-sided tape. Ideally, with double-sided thermal tape.
<img src="doc/cam_thermal.jpg" width=50% height=50%>
- Setting **log level** and getting logs from the camera. To get the logos, it is necessary to have a micro SD card formatted to **FAT32** inserted in the camera!
- Check the status of uploading the image to Prusa Connect using the **PrusaConnect Status:** variable
<a name="service_ap"></a>
## Service AP
After powering on and booting up the camera, it enters **AP mode**, which serves as a configuration mode for the camera. Essentially, it starts its own Wi-Fi network. The network name (SSID) is **ESP32_camera_UID**, where **UID** is the first three numbers from the **MCU ID**, serving as a unique identifier for the camera. The password for connecting to the AP is **12345678**. The camera's IP address is **192.168.0.1**. To configure the camera via **AP mode**, you need to connect to this IP address using a web browser: **http://192.168.0.1**. Alternatively, you can also use the **http://prusa-esp32cam.local** hostname (**mDNS**) instead of the IP address.
After powering on and booting up the camera, it enters **AP mode**, which serves as a configuration mode for the camera. Essentially, it starts its own Wi-Fi network. The network name (SSID) is **ESP32_camera_UID**, where **UID** is the first three numbers from the **MCU ID**, serving as a unique identifier for the camera. The password for connecting to the AP is **12345678**. The camera's IP address is **192.168.0.1**. To configure the camera via **AP mode**, you need to connect to this IP address using a web browser: **http://192.168.0.1**. Alternatively, you can also use the **http://prusa-esp32cam.local** hostname (**mDNS**) instead of the IP Address.
After establishing a successful connection, your computer might display a "**No Internet**" warning for the given network. **This is normal**.
If you have set up a Wi-Fi network name (SSID) and password in the camera for it to connect to, then upon powering on, the camera will automatically connect to the configured Wi-Fi network and simultaneously activate AP mode for **5 minutes**. AP mode is always enabled after powering on and booting up the camera for **5 minutes**. The service Wi-Fi AP **automatically deactivates** itself after **5 minutes** following each camera startup if no device is connected to the camera.
If you have set up a Wi-Fi network name (SSID) and password in the camera for it to connect to, then upon powering on, the camera will automatically connect to the configured Wi-Fi network and simultaneously activate AP mode for **5 minutes**. AP mode is always enabled after powering on and booting up the camera for **5 minutes**. The service Wi-Fi AP is **automatically deactivates** itself after **5 minutes** following each camera startup if no device is connected to the camera.
Service AP is for the first camera configuration. If the camera is connected to a WiFi network, it is possible to configure it from the local network.
Service AP is for for the first camera configuration. If the camera is connected to a WiFi network, it is possible to configure it from the local network.
<a name="factory_cfg"></a>
## How to reset configuration to factory settings
Each version of the [supported boards](#supported_boards) uses a different pin for camera reset. Therefore, it is necessary to refer to the documentation of the specific board to determine which pin is used to reset the camera configuration to factory defaults.
To reset the settings to factory defaults, follow these instructions:
The procedure is the same for each board:
- Ground the pin for camera reset configuration.
- Connect the power supply.
- Wait for 10 seconds.
- An LED will start blinking (refer to the board's documentation).
- Disconnect the ground from the camera reset configuration pin.
- The LED will stop blinking.
- The camera configuration will be reset to factory defaults.
<img src="doc/factory_cfg.jpg" width=30% height=30%>
- Connect PIN **IO12** to **ground**.
- **Plug in** the power supply.
- Wait for **10 seconds**.
- After 10 seconds, the **FLASH LED will start flashing**.
- **Disconnect** PIN **IO12** from **ground** (but don't disconnect the power supply).
- After disconnecting **IO12** from **ground**, the **FLASH LED** will **stop flashing**, and the MCU will **automatically reboot**.
- Now the MCU is in the factory settings.
<a name="status_led"></a>
## Status LED
On the board, there is a status LED that provides a visual indicator of the module's current status through blinking at defined intervals. Each [supported board](#supported_boards) has the STATUS LED located in a different place. It is necessary to refer to the documentation to locate the STATUS LED on the board.
On the board, there is a status LED that provides a visual indicator of the module's current status
through blinking at defined intervals.
Upon module activation, the LED illuminates. After processor initialization, the LED exhibits different blinking intervals based on the current mode of the module:
<img src="doc/status_led.jpg" width=25% height=25%>
Upon module activation, the LED illuminates. After processor initialization, the LED exhibits different blinking intervals based on the current mode of the module
- **Service AP Mode only:** The LED blinks every **400 ms**, indicating the module's availability in service AP mode.
- **Connecting to WiFi AP:** While connecting to a WiFi Access Point, the LED blinks at an interval of **800 ms**.
- **Connected to WiFi Network:** Upon successful connection to a WiFi network, the LED blinks at an interval of **4000 ms**, signaling a stable connection.
- **Connecting to WiFi AP:** While connecting to a WiFi Access Point, the LED blinks at intervals of **800 ms**.
- **Connected to WiFi Network:** Upon successful connection to a WiFi network, the LED blinks at intervals of **4000 ms**, signaling a stable connection.
- **Problematic State:** If an issue or error occurs, the LED accelerates its blinking to every **100 ms**.
The approximate boot time of the device is 15-20 seconds.
<a name="schematic"></a>
## Schematic for ESP32-cam board
<img src="doc/ESP32-CAM-AI-Thinker-schematic-diagram.png" width=70% height=70%>
Board description
<img src="doc/esp32-cam_parts.jpg" width=50% height=50%>
Pinout
<img src="doc/pinout.png" width=50% height=50%>
<a name="led_issue"></a>
## FLASH LED issue
The board has a problem with the FLASH LED, as it lacks any current limitation for the LED. Consequently, frequent use of the FLASH LED can lead to malfunction, due to excessive current flow.
One simple solution is to connect an external LED via a relay, transistor, or MOSFET to the board, as shown in the next picture. Using a relay is not ideal, but it provides a simple solution.
<img src="doc/relay_flash_bb.png" width=40% height=40%>
Another solution is to use an LED COB or a USB LED lamp. I utilized a board from a simple USB LED lamp. The transistor has a current limitation of 500mA, and my USB lamp has a current consumption of approximately 180mA. The original LED has a current consumption of 60-80mA. After calculation, the total current consumption is approximately 260mA, which falls within the current limitation of the transistor. Therefore, it is possible to solder the negative wire from the COB LED or the USB LED lamp to the transistor. The positive wire needs to be soldered to +5V.
This is my USB LED lamp
<img src="doc/usb_lamp.jpg" width=40% height=40%>
The next step is to solder the negative wire from the LED lamp to the transistor collector, and the positive wire from the LED lamp to the +5V on the board.
<img src="doc/esp32-cam_with_led_lamp.jpg" width=40% height=40%>
The third option is to solder a resistor between the collector of the transistor and the PCB. I used a 10-ohm resistor in a 0603 package. This option is more complicated for users with limited soldering experience.
<img src="doc/esp32-cam_flash_led_resistor.jpg" width=40% height=40%>
<a name="ext_wifi"></a>
## External/internal WiFi antenna
The standard ESP32-CAM board utilizes an internal antenna on the PCB. However, this antenna can sometimes cause issues with the quality of the WiFi signal, leading to slow photo uploads to PrusaConnect or connectivity problems. Fortunately, there is an option to connect an external antenna. This requires changing the resistor position, as shown in the picture below. Then, you can use a 2.4GHz Wi-Fi cable with a U.FL to RP-SMA connector and a standard 2.4GHz WiFi antenna
<img src="doc/esp32-cam_ext_ant.png" width=40% height=40%>
<a name="power_supply"></a>
## Power Supply
The device requires a 5V power supply, with a maximum current consumption of 2A. Power is supplied via a micro USB connector when using the original programmer.
<a name="logs"></a>
## Debug logs
It is possible to save debug logs to a microSD card, but the card must be formatted to FAT32. Currently, the maximum tested capacity for a microSD card is 16GB. If a microSD card is inserted into the camera, it is necessary to reboot the camera. When a microSD card is inserted into the camera before boot, logging to the microSD card is automatically enabled. If no microSD card is inserted, logging to the microSD card is automatically disabled. Enabling the saving of debug logs to a microSD card is only possible during camera boot, so it is necessary to restart the camera after inserting the microSD card. Debug logs are saved as plain text in the file `SysLog.log`.
It is possible to save debug logs to a microSD card, but the card must be formatted to FAT32. Currently, the maximum tested capacity for a microSD card is 16GB. If a microSD card is inserted into the camera, it is necessary to reboot the camera. When a microSD card is inserted into the camera before boot, logging to the microSD card is automatically enabled. If no microSD card is inserted, the saving of debug logs to the microSD card is automatically disabled. Enabling the saving of debug logs to a microSD card is only possible during camera boot, so it is necessary to restart the camera after inserting the microSD card. Debug logs are saved as plain text in the file Syslog.log
<a name="serial_cfg"></a>
## Serial console configuration
It is possible to set the basic camera configuration using the serial console. Serial port settings for communication with the MCU need to be set to **115200 8N1**.
Currently, it is possible to set the basic camera configuration using the serial console. Baud speed for communication with MCU is **115200 8N1**
Commands for configuration have a simple syntax:
Commands for configuration have simple syntax
| command | separator | variable | termination | line terminator |
|--------------|-----------|-----------|-------------|--------------------------|
@ -220,16 +339,10 @@ Currently, available commands are listed in the table below:
| mcureboot | Rebooting the MCU |
| commandslist | Listing currently supported commands via serial console |
| getwifimode | Print current WiFi mode. STA/AP/AP+STA |
| getwifistastatus | Print WiFi STA status. Connected/Disconnected/Connecting... |
| getwifistastatus | Print WiFi STA status. Connected/Disconnected/Connecting.... |
| getwifistaip | Print IP address for WiFi STA |
| getserviceapssid | Print service AP SSID name |
| setauthtoken | Set authentication token for Prusa Connect |
| otaupdate | Start OTA update process |
| resolution | Set photo resolution |
| photoquality | Set photo quality |
| setflash | Enable/disable LED flash |
| setlight | Enable/disable LED light |
| loglevel | Set log level. 0=Error, 1=Warning, 2=Info, 3=Verbose |
| setauthtoken: | Set authentication token for Prusa Connect |
The standard command sequence for camera basic settings is
@ -239,68 +352,9 @@ The standard command sequence for camera basic settings is
- setauthtoken:TOKEN;
- mcureboot;
<a name="rest"></a>
## WEB API
The camera offers a web API, allowing several operations to be performed through the web interface:
| Command | Description |
|---------------------------|--------------------------------------------------|
| http://IP/action_capture | Capture snapshot |
| http://IP/action_send | Capture snapshot, and send to Prusa Connect |
| http://IP/light?on | Light ON |
| http://IP/light?off | Light OFF |
| http://IP/flash?on | FLASH ON |
| http://IP/flash?off | FLASH OFF |
| http://IP/action_reboot | Reboot MCU |
| http://IP/get_logs | Get logs from micro SD card |
| http://IP/saved-photo.jpg | Get last captured photo |
| http://IP/get_temp | Get temperature from external sensor |
| http://IP/get_hum | Get humidity from external sensor |
<a name="stream"></a>
## Video stream
The video stream is available at **http://IP/stream.mjpg**.
<a name="man_focus"></a>
## Manual camera focus
Usually, the camera module is properly focused. However, the camera module can be manually focused. There are several types of lenses for camera modules. I have created several [tools](https://www.printables.com/cs/model/877739-esp32-cam-ov2640-focus-adjustment-wrench) for manually focusing the camera module.
<img src="doc/focus_2.jpg" width=40% height=40%>
First, it is necessary to hold the camera with a holder and then put the wrench on the lens. Next, gently turn the wrench by a couple of degrees, and observe the difference.
**WARNING! Manual focusing can permanently damage the camera module!**
<a name="ext_temp"></a>
## External temperature sensor
The software supports an external temperature sensor **DHT22** or **DHT11**. The sensor needs to be connected according to the manual for the specific version of the board. The temperature and humidity are automatically read every 30 seconds once the sensor has been enabled.
<img src="doc/Sensori-DHT11-e-DHT22.jpg" width=40% height=40%>
Information about sensors:
| | DHT11 | DHT22 |
|-------------------|--------------|------------------|
| Operating voltage | 3-5V | 3-5V |
| Max current | 2.5 mA | 2.5mA |
| Temperature range | 0-50°C ± 2°C | -40-80°C ± 0.5°C |
| Humidity range | 20-80% / 5% | 0-100% / 2-5% |
| Sampling rate | 1Hz | 0.5Hz |
It is necessary to use the **module**, **not the sensor**! The module with the sensor has a **4.7kOhm** resistor soldered onto the PCB, which is necessary for the **one-wire bus** to operate properly. If you use the sensor, it is necessary to connect a 4.7kOhm resistor to the one-wire bus as shown in the schematic below. **The module must be powered with 3.3V VCC, otherwise it may damage the camera board**.
Here is a typical schematic for the DHT22 or DHT11 sensor:
<img src="doc/DHT22-Schematic.png" width=40% height=40%>
<a name="issue"></a>
## Troubleshooting
## Potential issue
- A potential issue may arise with connecting to the service AP. If the connection fails and an authentication error occurs, it is necessary to clear the FLASH memory of the processor, and FLASH FW again. This can be done either through the Arduino IDE or using official software.
- After the initial firmware upload to a new camera, there may be an issue when connecting to the IP address, where the camera prompts for a username and password to access the web page. Even when entering the username "admin" and the password "admin", the login still doesn't work. In such cases, it's necessary to reset the camera configuration to factory settings. The procedure is outlined in the readme file [here](#factory_cfg).
- If you are getting a 400 return code from Prusa Connect, then you need to create another camera in Prusa Connect and enter a new token into the ESP32 camera.
- If you are getting a 404 return code from Prusa Connect, it may indicate that the printer is powered off. The printer must be powered on in order for images to be uploaded.
- While sending the photo to the backend, the WEB server is temporarily disabled for this short interval. After the photo is sent to the backend, the WEB server is re-enabled. This may cause short unavailability in the WEB server on the camera, lasting several seconds, depending on the internet connection and the quality of the WiFi connection
- After the initial firmware upload to the new camera, there may be an issue when connecting to the IP address, where the camera prompts for a username and password to access the web page. Even when entering the username "admin" and the password "admin", the login still doesn't work. In such cases, it's necessary to reset the camera configuration to factory settings. The procedure is outlined in the readme file [here](#factory_cfg)

Binary file not shown.

Before

Width:  |  Height:  |  Size: 65 KiB

View File

@ -1,254 +0,0 @@
# Ai Thinker ESP32-CAM
What we need for functionality
- ESP32-CAM AI-thinker board with OV2640 camera module [ here ](#esp32)
- Supported camera modules [here](#cam_modules)
- Module board version [here](#different_mcu)
- How to flash binary files to board from Linux/MAC/Windows [ here ](#flash_fw)
- How to compile software in the Arduino IDE [ here ](#arduino_cfg)
- How to reset the configuration to factory settings [here](#factory_cfg)
- Status LED [ here ](#status_led)
- Schematic main board is [here](#schematic)
- Issue with FLASH LED on the main board [here](#led_issue)
- External WiFi antenna [here](#ext_wifi)
- Power supply [here](#power_supply)
- External temperature sensor DHT22/DHT11 [here](#ext_sens)
- Potential issue [here](#issue)
<a name="esp32"></a>
## ESP32-CAM AI-thinker board
Basic information:
- Low cost version
- FLASH LED on the board
- Option connecting external FLASH LED
- Micro SD card slot
- Internal WiFi antenna, after HW modification it's possible connecting external antenna
- Additional HW must be purchased for programming
- 4MB FLASH and 4MB external PSRAM
- 520 KB SRAM
It's a few dollars board with **ESP32** MCU and Camera. It's necessary to buy a board with **camera module OV2640**. The board is sold without a programmer by default. It is possible to program it using the FTDI USB to UART converter, or purchase an official programmer for the board. We recommend purchasing an official programmer. It can save a lot of trouble with connecting and programming the board. There are currently [2 different board versions](#different_mcu), but only one is compatible with the official programmer.
<img src="esp32-cam.jpg" width=30% height=30%>
In the following picture, we can see the **ESP32-CAM** board and the programmer for the board.
<img src="esp32_and_prog.jpg" width=30% height=30%>
<a name="cam_modules"></a>
## Supported camera modules
It's necessary to use a camera version **OV2640**. If using a different camera, modification of the camera's pinout can be needed, or some camera settings may not work correctly. We recommend to use a camera module with a viewing angle of 120° or 160°.
These are currently known or tested camera modules:
| Camera chip | FOV | Resolution | Tested | Works | Description |
|-------------|------|------------|--------|-------|------------------------------------------|
| OV2640 | 30° | 2MP | No | N/A | |
| OV2640 | 44° | 2MP | No | N/A | |
| OV2640 | 66° | 2MP | Yes | Yes | Recommended. Standard camera module |
| OV2640 | 120° | 2MP | Yes | Yes | Recommended |
| OV2640 | 160° | 2MP | Yes | Yes | Recommended |
| OV2640 | 200° | 2MP | No | N/A | |
| OV2640 | 222° | 2MP | No | N/A | |
| OV2640IR | 160° | 2MP | Yes | Yes | |
| OV8225N | 66° | 2MP | Yes | Yes | |
| OV3360 | 66° | 3MP | Yes | Yes | |
| OV5640-AF | 72° | 5MP | Yes | Yes | Overheating, slow photo loading |
<a name="different_mcu"></a>
## Different MCU version
There are currently 2 versions of the board, but only one version is possible programming via oficial **CH340** programmer. The blue rectangle shows the differences between the HW versions.
<img src="cam_versions.jpg" width=50% height=50%>
The red arrow points to a pin that differs between these boards. In version 1, this pin is used for **MCU RESET (GND/R)**. In version 2, this pin serves as ground **(GND)**. Version 1 can be programmed via **CH340**, whereas version 2 cannot be programmed via **CH340**. For version 2, we tested programming via **FT232RL** or **CP2102**, and the programming process worked successfully.
If we want to program the MCU without the original programmer with **CH340**, or if we want to program the second version of the board, then we need to follow the following instructions. We will need a USB to UART converter, such as **FT232**, **CP2102** or **CH340**. I have tested firmware uploading to the **ESP32-cam** with these converters. Uploading FW to the **second** version using **CH340** did not work for me. Uploading FW using **CH340** only worked for me for the first version of **ESP32-cam** board. For the next steps, I will use the **FT232RL** converter. We connect the **ESP32-cam** to the **FT232** according to the following diagram, where we connect:
<img src="ESP32-cam prog_bb.png" width=60% height=60%>
- **VCC** from **FT232** to **5V** on the **ESP32-CAM**. **CAUTION!** It is necessary to observe the maximum supply voltage of the **ESP32-CAM**, otherwise irreversible damage to the **ESP32-CAM** module may occur.
- **GND** from **FT232** to **GND** on the **ESP32-CAM**
- **TX** from **FT232** to **U0R** on the **ESP32-CAM**
- **RX** from **FT232** to **U0T** on the **ESP32-CAM**
- **IO0** from **ESP32-CAM** to **GND** on **ESP32-CAM**. By connecting the **IO0** pin to **GND**, we switch the board to the mode in which it expects firmware uploading.
Next step is connect the **FT232** converter to the PC and install the correct driver. Then we proceed with uploading the firmware to the **ESP32-cam**, which is described [here](https://github.com/prusa3d/Prusa-Firmware-ESP32-Cam?tab=readme-ov-file#how-to-flash-binary-files-to-esp32-cam-board-from-linuxmacwindows). After successfully uploading the firmware to the **ESP32-cam**, we disconnect **IO0** from **GND**, disconnect the **FT232** converter from the **ESP32-CAM**, and connect the **ESP32-CAM** to the power supply.
The recommended version includes the MCU ESP32 (ESP32-S) with 520 KB of SRAM and external 4M PSRAM
<a name="flash_fw"></a>
## How to flash binary files to board from Linux/MAC/Windows
#### Partitions table for flashing FW
Here is the partitions table:
| Name | Type | SubType | Offset | Size | Flags |
|---------|---------|---------|----------|----------|-------|
| nvs | data | nvs | 0x9000 | 0x5000 | |
| otadata | data | ota | 0xe000 | 0x2000 | |
| app0 | app | ota_0 | 0x10000 | 0x1E0000 | |
| app1 | app | ota_1 | 0x1F0000 | 0x1E0000 | |
| spiffs | data | spiffs | 0x3D0000 | 0x20000 | |
| coredump| data | coredump| 0x3F0000 | 0x10000 | |
However, for uploading the firmware, it's important to use this configuration of addresses and files:
ZIP file with build binary files: **esp32-cam.zip**
- address **0x1000** - **ESP32_PrusaConnectCam.ino.bootloader.bin**
- address **0x8000** - **ESP32_PrusaConnectCam.ino.partitions.bin**
- address **0x10000** - **ESP32_PrusaConnectCam.ino.bin**
**It is important to download the correct binary files! Each type of camera has its own ZIP archive with files for uploading the firmware.**
#### Linux/MAC
You must use the console to upload the firmware on the MAC or Linux platform. First, ensure you have installed esptool for Python. You can find it on the manufacturer's website, ESPRESSIF, [here](https://docs.espressif.com/projects/esp-at/en/latest/esp32/Get_Started/Downloading_guide.html#linux-or-macos).
And command for FLASH FW is here, where **/dev/ttya0** is your serial interface for communication with the ESP32-cam board. This is the command for the first flash FW to MCU.
```
./esptool -p /dev/ttya0 -b 460800 --before default_reset --after hard_reset --chip esp32 write_flash --erase-all --flash_mode dio --flash_size 4MB --flash_freq 80m 0x1000 ESP32_PrusaConnectCam.ino.bootloader.bin 0x8000 ESP32_PrusaConnectCam.ino.partitions.bin 0x10000 ESP32_PrusaConnectCam.ino.bin
```
This command contains the parameter **--erase-all**, which erases the entire flash in the MCU. So, for just updating the firmware, it is necessary to remove the parameter **--erase-all**; otherwise, the MCU configuration will also be deleted. The basic command list can be found [here](https://docs.espressif.com/projects/esptool/en/latest/esp32s3/esptool/basic-commands.html)
Here is the command for updating the firmware in the MCU without erasing the MCU configuration
```
./esptool -p /dev/ttya0 -b 460800 --before default_reset --after hard_reset --chip esp32 write_flash --flash_mode dio --flash_size 4MB --flash_freq 80m 0x1000 ESP32_PrusaConnectCam.ino.bootloader.bin 0x8000 ESP32_PrusaConnectCam.ino.partitions.bin 0x10000 ESP32_PrusaConnectCam.ino.bin
```
Launching the esptool application may be different in different operating systems
#### Windows
Driver for CH340 USB to UART convert for Windows is for example [here](https://www.wch-ic.com/search?q=CH340&t=downloads) . An older version of the driver is for example [here](https://blog.laskakit.cz/wp-content/uploads/2020/03/CH341SER.zip). SW for FW flash (Flash Download Tools) is [here](https://www.espressif.com/en/support/download/other-tools)
<img src="how to flash chip select.jpg" width=25% height=25%>
It's necessary to erase the FLASH using the **ERASE** button before the first firmware flash.
<img src="how to flash.jpg" width=30% height=30%>
<a name="arduino_cfg"></a>
## How to compile software in the Arduino IDE
Board configuration in the Arduino IDE 2.3.2
- Tools -> Board -> ESP32 Arduino -> AI Thinker ESP32
- Tools -> Flash frequency -> 80MHz
- Tools -> Core Debug Level -> None
- Tools -> Erase all Flash Before Sketch Upload -> Disable **(first flash, new board = enable. otherwise = disable)**
- Tools -> Flash Mode -> DIO
- Tools -> Partition scheme -> Minimal SPIFFS (1.9MB APP with OTA/190KB SPIFFS)
When flashing the firmware to a new, empty ESP32-CAM device for the first time, it is necessary to use the 'Erase' function.
This can be found under **Tools** -> **Erase all Flash Before Sketch Upload** -> **Enable**.
After the initial firmware upload to the MCU, it's necessary to disable this option. If you do not disable this option, your camera configuration will continue to be erased from the flash memory after uploading new firmware from the Arduino IDE.
It is necessary to enable support for the correct board version in the file **mcu_cfg.h** after line 16.
<a name="factory_cfg"></a>
## How to reset configuration to factory settings
To reset the settings to factory defaults, follow these instructions:
<img src="factory_cfg.jpg" width=30% height=30%>
- Connect PIN **IO12** to **ground**.
- **Plug in** the power supply.
- Wait for **10 seconds**.
- After 10 seconds, the **FLASH LED will start flashing**.
- **Disconnect** PIN **IO12** from **ground** (but don't disconnect the power supply).
- After disconnecting **IO12** from **ground**, the **FLASH LED** will **stop flashing**, and the MCU will **automatically reboot**.
- Now the MCU is in the factory settings.
<a name="status_led"></a>
## Status LED
On the board, there is a status LED that provides a visual indicator of the module's current status
through blinking at defined intervals.
<img src="status_led.jpg" width=25% height=25%>
Upon module activation, the LED illuminates. After processor initialization, the LED exhibits different blinking intervals based on the current mode of the module
- **Service AP Mode only:** The LED blinks every **400 ms**, indicating the module's availability in service AP mode.
- **Connecting to WiFi AP:** While connecting to a WiFi Access Point, the LED blinks at intervals of **800 ms**.
- **Connected to WiFi Network:** Upon successful connection to a WiFi network, the LED blinks at intervals of **4000 ms**, signaling a stable connection.
- **Problematic State:** If an issue or error occurs, the LED accelerates its blinking to every **100 ms**.
The approximate boot time of the device is 15-20 seconds.
<a name="schematic"></a>
## Schematic for ESP32-cam board
<img src="ESP32-CAM-AI-Thinker-schematic-diagram.png" width=70% height=70%>
Board description
<img src="esp32-cam_parts.jpg" width=50% height=50%>
Pinout
<img src="pinout.png" width=50% height=50%>
<a name="led_issue"></a>
## FLASH LED issue
The board has a problem with the FLASH LED, as it lacks any current limitation for the LED. Consequently, frequent use of the FLASH LED can lead to malfunction, due to excessive current flow.
One simple solution is to connect an external LED via a relay, transistor, or MOSFET to the board, as shown in the next picture. Using a relay is not ideal, but it provides a simple solution.
<img src="relay_flash_bb.png" width=40% height=40%>
Another solution is to use an LED COB or a USB LED lamp. I utilized a board from a simple USB LED lamp. The transistor has a current limitation of 500mA, and my USB lamp has a current consumption of approximately 180mA. The original LED has a current consumption of 60-80mA. After calculation, the total current consumption is approximately 260mA, which falls within the current limitation of the transistor. Therefore, it is possible to solder the negative wire from the COB LED or the USB LED lamp to the transistor. The positive wire needs to be soldered to +5V.
This is my USB LED lamp
<img src="usb_lamp.jpg" width=40% height=40%>
The next step is to solder the negative wire from the LED lamp to the transistor collector, and the positive wire from the LED lamp to the +5V on the board.
<img src="esp32-cam_with_led_lamp.jpg" width=40% height=40%>
The third option is to solder a resistor between the collector of the transistor and the PCB. I used a 10-ohm resistor in a 0603 package. This option is more complicated for users with limited soldering experience.
<img src="esp32-cam_flash_led_resistor.jpg" width=40% height=40%>
<a name="ext_wifi"></a>
## External/internal WiFi antenna
The standard ESP32-CAM board utilizes an internal antenna on the PCB. However, this antenna can sometimes cause issues with the quality of the WiFi signal, leading to slow photo uploads to PrusaConnect or connectivity problems. Fortunately, there is an option to connect an external antenna. This requires changing the resistor position, as shown in the picture below. Then, you can use a 2.4GHz Wi-Fi cable with a U.FL to RP-SMA connector and a standard 2.4GHz WiFi antenna
<img src="esp32-cam_ext_ant.png" width=40% height=40%>
<a name="power_supply"></a>
## Power Supply
The device requires a 5V power supply, with a maximum current consumption of 2A. Power is supplied via a micro USB connector when using the original programmer.
<a name="ext_sens"></a>
## External temperature sensor DHT22/DHT11
Below you will find the wiring diagram for the DHT22 or DHT11 sensor.
| Camera board | DHT22/DHT11 |
|--------------|-------------|
| 3.3V | VCC |
| GND | GND |
| IO13 | Data |
<img src="ESP32-cam dht22_bb.png" width=40% height=40%>
<a name="issue"></a>
## Potential issue with this board
- The flash LED may fail after some time due to the absence of a current-limiting resistor.
- The WiFi signal quality on this board may be weaker compared to other boards and may degrade over time.

Binary file not shown.

Before

Width:  |  Height:  |  Size: 118 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 16 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 29 KiB

View File

Before

Width:  |  Height:  |  Size: 199 KiB

After

Width:  |  Height:  |  Size: 199 KiB

View File

@ -1,157 +0,0 @@
#include "esp_camera.h"
#include <WiFi.h>
//
// WARNING!!! PSRAM IC required for UXGA resolution and high JPEG quality
// Ensure ESP32 Wrover Module or other board with PSRAM is selected
// Partial images will be transmitted if image exceeds buffer size
//
// You must select partition scheme from the board menu that has at least 3MB APP space.
// Face Recognition is DISABLED for ESP32 and ESP32-S2, because it takes up from 15
// seconds to process single frame. Face Detection is ENABLED if PSRAM is enabled as well
// ===================
// Select camera model
// ===================
//#define CAMERA_MODEL_WROVER_KIT // Has PSRAM
//#define CAMERA_MODEL_ESP_EYE // Has PSRAM
#define CAMERA_MODEL_ESP32S3_EYE // Has PSRAM
//#define CAMERA_MODEL_M5STACK_PSRAM // Has PSRAM
//#define CAMERA_MODEL_M5STACK_V2_PSRAM // M5Camera version B Has PSRAM
//#define CAMERA_MODEL_M5STACK_WIDE // Has PSRAM
//#define CAMERA_MODEL_M5STACK_ESP32CAM // No PSRAM
//#define CAMERA_MODEL_M5STACK_UNITCAM // No PSRAM
//#define CAMERA_MODEL_AI_THINKER // Has PSRAM
//#define CAMERA_MODEL_TTGO_T_JOURNAL // No PSRAM
//#define CAMERA_MODEL_XIAO_ESP32S3 // Has PSRAM
// ** Espressif Internal Boards **
//#define CAMERA_MODEL_ESP32_CAM_BOARD
//#define CAMERA_MODEL_ESP32S2_CAM_BOARD
//#define CAMERA_MODEL_ESP32S3_CAM_LCD
//#define CAMERA_MODEL_DFRobot_FireBeetle2_ESP32S3 // Has PSRAM
//#define CAMERA_MODEL_DFRobot_Romeo_ESP32S3 // Has PSRAM
#include "camera_pins.h"
// ===========================
// Enter your WiFi credentials
// ===========================
const char* ssid = "sparkleiot";
const char* password = "12345678";
void startCameraServer();
void setupLedFlash(int pin);
void setup() {
Serial.begin(115200);
Serial.setDebugOutput(true);
Serial.println();
camera_config_t config;
config.ledc_channel = LEDC_CHANNEL_0;
config.ledc_timer = LEDC_TIMER_0;
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_sccb_sda = SIOD_GPIO_NUM;
config.pin_sccb_scl = SIOC_GPIO_NUM;
config.pin_pwdn = PWDN_GPIO_NUM;
config.pin_reset = RESET_GPIO_NUM;
config.xclk_freq_hz = 20000000;
config.frame_size = FRAMESIZE_QVGA;
//config.pixel_format = PIXFORMAT_JPEG; // for streaming
config.pixel_format = PIXFORMAT_RGB565; // for face detection/recognition
config.grab_mode = CAMERA_GRAB_WHEN_EMPTY;
config.fb_location = CAMERA_FB_IN_PSRAM;
config.jpeg_quality = 12;
config.fb_count = 1;
// if PSRAM IC present, init with UXGA resolution and higher JPEG quality
// for larger pre-allocated frame buffer.
if(config.pixel_format == PIXFORMAT_JPEG){
if(psramFound()){
config.jpeg_quality = 10;
config.fb_count = 2;
config.grab_mode = CAMERA_GRAB_LATEST;
} else {
// Limit the frame size when PSRAM is not available
config.frame_size = FRAMESIZE_SVGA;
config.fb_location = CAMERA_FB_IN_DRAM;
}
} else {
// Best option for face detection/recognition
config.frame_size = FRAMESIZE_QVGA;
#if CONFIG_IDF_TARGET_ESP32S3
config.fb_count = 2;
#endif
}
#if defined(CAMERA_MODEL_ESP_EYE)
pinMode(13, INPUT_PULLUP);
pinMode(14, INPUT_PULLUP);
#endif
// 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;
}
sensor_t * s = esp_camera_sensor_get();
// initial sensors are flipped vertically and colors are a bit saturated
if (s->id.PID == OV3660_PID) {
s->set_vflip(s, 1); // flip it back
s->set_brightness(s, 1); // up the brightness just a bit
s->set_saturation(s, -2); // lower the saturation
}
// drop down frame size for higher initial frame rate
if(config.pixel_format == PIXFORMAT_JPEG){
s->set_framesize(s, FRAMESIZE_QVGA);
}
#if defined(CAMERA_MODEL_M5STACK_WIDE) || defined(CAMERA_MODEL_M5STACK_ESP32CAM)
s->set_vflip(s, 1);
s->set_hmirror(s, 1);
#endif
#if defined(CAMERA_MODEL_ESP32S3_EYE)
s->set_vflip(s, 1);
#endif
// Setup LED FLash if LED pin is defined in camera_pins.h
#if defined(LED_GPIO_NUM)
setupLedFlash(LED_GPIO_NUM);
#endif
Serial.println("The device needs to be linked to a 2.4G router........");
Serial.println("SSSID:sparkleiot");
Serial.println("Password:12345678");
WiFi.begin(ssid, password);
WiFi.setSleep(false);
while (WiFi.status() != WL_CONNECTED) {
delay(500);
Serial.print(".");
}
Serial.println("");
Serial.println("WiFi connected");
startCameraServer();
Serial.print("Camera Ready! Use 'http://");
Serial.print(WiFi.localIP());
Serial.println("' to connect");
}
void loop() {
// Do nothing. Everything is done in another task by the web server
delay(10000);
}

View File

@ -1,318 +0,0 @@
#if defined(CAMERA_MODEL_WROVER_KIT)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM -1
#define XCLK_GPIO_NUM 21
#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 19
#define Y4_GPIO_NUM 18
#define Y3_GPIO_NUM 5
#define Y2_GPIO_NUM 4
#define VSYNC_GPIO_NUM 25
#define HREF_GPIO_NUM 23
#define PCLK_GPIO_NUM 22
#elif defined(CAMERA_MODEL_ESP_EYE)
#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
// 4 for flash led or 33 for normal led
#define LED_GPIO_NUM 4
#elif defined(CAMERA_MODEL_M5STACK_PSRAM)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM 15
#define XCLK_GPIO_NUM 27
#define SIOD_GPIO_NUM 25
#define SIOC_GPIO_NUM 23
#define Y9_GPIO_NUM 19
#define Y8_GPIO_NUM 36
#define Y7_GPIO_NUM 18
#define Y6_GPIO_NUM 39
#define Y5_GPIO_NUM 5
#define Y4_GPIO_NUM 34
#define Y3_GPIO_NUM 35
#define Y2_GPIO_NUM 32
#define VSYNC_GPIO_NUM 22
#define HREF_GPIO_NUM 26
#define PCLK_GPIO_NUM 21
#elif defined(CAMERA_MODEL_M5STACK_V2_PSRAM)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM 15
#define XCLK_GPIO_NUM 27
#define SIOD_GPIO_NUM 22
#define SIOC_GPIO_NUM 23
#define Y9_GPIO_NUM 19
#define Y8_GPIO_NUM 36
#define Y7_GPIO_NUM 18
#define Y6_GPIO_NUM 39
#define Y5_GPIO_NUM 5
#define Y4_GPIO_NUM 34
#define Y3_GPIO_NUM 35
#define Y2_GPIO_NUM 32
#define VSYNC_GPIO_NUM 25
#define HREF_GPIO_NUM 26
#define PCLK_GPIO_NUM 21
#elif defined(CAMERA_MODEL_M5STACK_WIDE)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM 15
#define XCLK_GPIO_NUM 27
#define SIOD_GPIO_NUM 22
#define SIOC_GPIO_NUM 23
#define Y9_GPIO_NUM 19
#define Y8_GPIO_NUM 36
#define Y7_GPIO_NUM 18
#define Y6_GPIO_NUM 39
#define Y5_GPIO_NUM 5
#define Y4_GPIO_NUM 34
#define Y3_GPIO_NUM 35
#define Y2_GPIO_NUM 32
#define VSYNC_GPIO_NUM 25
#define HREF_GPIO_NUM 26
#define PCLK_GPIO_NUM 21
#define LED_GPIO_NUM 2
#elif defined(CAMERA_MODEL_M5STACK_ESP32CAM)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM 15
#define XCLK_GPIO_NUM 27
#define SIOD_GPIO_NUM 25
#define SIOC_GPIO_NUM 23
#define Y9_GPIO_NUM 19
#define Y8_GPIO_NUM 36
#define Y7_GPIO_NUM 18
#define Y6_GPIO_NUM 39
#define Y5_GPIO_NUM 5
#define Y4_GPIO_NUM 34
#define Y3_GPIO_NUM 35
#define Y2_GPIO_NUM 17
#define VSYNC_GPIO_NUM 22
#define HREF_GPIO_NUM 26
#define PCLK_GPIO_NUM 21
#elif defined(CAMERA_MODEL_M5STACK_UNITCAM)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM 15
#define XCLK_GPIO_NUM 27
#define SIOD_GPIO_NUM 25
#define SIOC_GPIO_NUM 23
#define Y9_GPIO_NUM 19
#define Y8_GPIO_NUM 36
#define Y7_GPIO_NUM 18
#define Y6_GPIO_NUM 39
#define Y5_GPIO_NUM 5
#define Y4_GPIO_NUM 34
#define Y3_GPIO_NUM 35
#define Y2_GPIO_NUM 32
#define VSYNC_GPIO_NUM 22
#define HREF_GPIO_NUM 26
#define PCLK_GPIO_NUM 21
#elif defined(CAMERA_MODEL_AI_THINKER)
#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
// 4 for flash led or 33 for normal led
#define LED_GPIO_NUM 4
#elif defined(CAMERA_MODEL_TTGO_T_JOURNAL)
#define PWDN_GPIO_NUM 0
#define RESET_GPIO_NUM 15
#define XCLK_GPIO_NUM 27
#define SIOD_GPIO_NUM 25
#define SIOC_GPIO_NUM 23
#define Y9_GPIO_NUM 19
#define Y8_GPIO_NUM 36
#define Y7_GPIO_NUM 18
#define Y6_GPIO_NUM 39
#define Y5_GPIO_NUM 5
#define Y4_GPIO_NUM 34
#define Y3_GPIO_NUM 35
#define Y2_GPIO_NUM 17
#define VSYNC_GPIO_NUM 22
#define HREF_GPIO_NUM 26
#define PCLK_GPIO_NUM 21
#elif defined(CAMERA_MODEL_XIAO_ESP32S3)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM -1
#define XCLK_GPIO_NUM 10
#define SIOD_GPIO_NUM 40
#define SIOC_GPIO_NUM 39
#define Y9_GPIO_NUM 48
#define Y8_GPIO_NUM 11
#define Y7_GPIO_NUM 12
#define Y6_GPIO_NUM 14
#define Y5_GPIO_NUM 16
#define Y4_GPIO_NUM 18
#define Y3_GPIO_NUM 17
#define Y2_GPIO_NUM 15
#define VSYNC_GPIO_NUM 38
#define HREF_GPIO_NUM 47
#define PCLK_GPIO_NUM 13
#elif defined(CAMERA_MODEL_ESP32_CAM_BOARD)
// The 18 pin header on the board has Y5 and Y3 swapped
#define USE_BOARD_HEADER 0
#define PWDN_GPIO_NUM 32
#define RESET_GPIO_NUM 33
#define XCLK_GPIO_NUM 4
#define SIOD_GPIO_NUM 18
#define SIOC_GPIO_NUM 23
#define Y9_GPIO_NUM 36
#define Y8_GPIO_NUM 19
#define Y7_GPIO_NUM 21
#define Y6_GPIO_NUM 39
#if USE_BOARD_HEADER
#define Y5_GPIO_NUM 13
#else
#define Y5_GPIO_NUM 35
#endif
#define Y4_GPIO_NUM 14
#if USE_BOARD_HEADER
#define Y3_GPIO_NUM 35
#else
#define Y3_GPIO_NUM 13
#endif
#define Y2_GPIO_NUM 34
#define VSYNC_GPIO_NUM 5
#define HREF_GPIO_NUM 27
#define PCLK_GPIO_NUM 25
#elif defined(CAMERA_MODEL_ESP32S3_CAM_LCD)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM -1
#define XCLK_GPIO_NUM 40
#define SIOD_GPIO_NUM 17
#define SIOC_GPIO_NUM 18
#define Y9_GPIO_NUM 39
#define Y8_GPIO_NUM 41
#define Y7_GPIO_NUM 42
#define Y6_GPIO_NUM 12
#define Y5_GPIO_NUM 3
#define Y4_GPIO_NUM 14
#define Y3_GPIO_NUM 47
#define Y2_GPIO_NUM 13
#define VSYNC_GPIO_NUM 21
#define HREF_GPIO_NUM 38
#define PCLK_GPIO_NUM 11
#elif defined(CAMERA_MODEL_ESP32S2_CAM_BOARD)
// The 18 pin header on the board has Y5 and Y3 swapped
#define USE_BOARD_HEADER 0
#define PWDN_GPIO_NUM 1
#define RESET_GPIO_NUM 2
#define XCLK_GPIO_NUM 42
#define SIOD_GPIO_NUM 41
#define SIOC_GPIO_NUM 18
#define Y9_GPIO_NUM 16
#define Y8_GPIO_NUM 39
#define Y7_GPIO_NUM 40
#define Y6_GPIO_NUM 15
#if USE_BOARD_HEADER
#define Y5_GPIO_NUM 12
#else
#define Y5_GPIO_NUM 13
#endif
#define Y4_GPIO_NUM 5
#if USE_BOARD_HEADER
#define Y3_GPIO_NUM 13
#else
#define Y3_GPIO_NUM 12
#endif
#define Y2_GPIO_NUM 14
#define VSYNC_GPIO_NUM 38
#define HREF_GPIO_NUM 4
#define PCLK_GPIO_NUM 3
#elif defined(CAMERA_MODEL_ESP32S3_EYE)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM -1
#define XCLK_GPIO_NUM 15
#define SIOD_GPIO_NUM 4
#define SIOC_GPIO_NUM 5
#define Y2_GPIO_NUM 11
#define Y3_GPIO_NUM 9
#define Y4_GPIO_NUM 8
#define Y5_GPIO_NUM 10
#define Y6_GPIO_NUM 12
#define Y7_GPIO_NUM 18
#define Y8_GPIO_NUM 17
#define Y9_GPIO_NUM 16
#define VSYNC_GPIO_NUM 6
#define HREF_GPIO_NUM 7
#define PCLK_GPIO_NUM 13
#elif defined(CAMERA_MODEL_DFRobot_FireBeetle2_ESP32S3) || defined(CAMERA_MODEL_DFRobot_Romeo_ESP32S3)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM -1
#define XCLK_GPIO_NUM 45
#define SIOD_GPIO_NUM 1
#define SIOC_GPIO_NUM 2
#define Y9_GPIO_NUM 48
#define Y8_GPIO_NUM 46
#define Y7_GPIO_NUM 8
#define Y6_GPIO_NUM 7
#define Y5_GPIO_NUM 4
#define Y4_GPIO_NUM 41
#define Y3_GPIO_NUM 40
#define Y2_GPIO_NUM 39
#define VSYNC_GPIO_NUM 6
#define HREF_GPIO_NUM 42
#define PCLK_GPIO_NUM 5
#else
#error "Camera model not selected"
#endif

View File

@ -1,5 +0,0 @@
# Name, Type, SubType, Offset, Size, Flags
nvs, data, nvs, 0x9000, 0x5000,
otadata, data, ota, 0xe000, 0x2000,
app0, app, ota_0, 0x10000, 0x3d0000,
fr, data, , 0x3e0000, 0x20000,
1 # Name Type SubType Offset Size Flags
2 nvs data nvs 0x9000 0x5000
3 otadata data ota 0xe000 0x2000
4 app0 app ota_0 0x10000 0x3d0000
5 fr data 0x3e0000 0x20000

View File

@ -1,157 +0,0 @@
#include "esp_camera.h"
#include <WiFi.h>
//
// WARNING!!! PSRAM IC required for UXGA resolution and high JPEG quality
// Ensure ESP32 Wrover Module or other board with PSRAM is selected
// Partial images will be transmitted if image exceeds buffer size
//
// You must select partition scheme from the board menu that has at least 3MB APP space.
// Face Recognition is DISABLED for ESP32 and ESP32-S2, because it takes up from 15
// seconds to process single frame. Face Detection is ENABLED if PSRAM is enabled as well
// ===================
// Select camera model
// ===================
//#define CAMERA_MODEL_WROVER_KIT // Has PSRAM
//#define CAMERA_MODEL_ESP_EYE // Has PSRAM
//define CAMERA_MODEL_ESP32S3_EYE // Has PSRAM
//#define CAMERA_MODEL_M5STACK_PSRAM // Has PSRAM
//#define CAMERA_MODEL_M5STACK_V2_PSRAM // M5Camera version B Has PSRAM
//#define CAMERA_MODEL_M5STACK_WIDE // Has PSRAM
//#define CAMERA_MODEL_M5STACK_ESP32CAM // No PSRAM
//#define CAMERA_MODEL_M5STACK_UNITCAM // No PSRAM
#define CAMERA_MODEL_AI_THINKER // Has PSRAM
//#define CAMERA_MODEL_TTGO_T_JOURNAL // No PSRAM
//#define CAMERA_MODEL_XIAO_ESP32S3 // Has PSRAM
// ** Espressif Internal Boards **
//#define CAMERA_MODEL_ESP32_CAM_BOARD
//#define CAMERA_MODEL_ESP32S2_CAM_BOARD
//#define CAMERA_MODEL_ESP32S3_CAM_LCD
//#define CAMERA_MODEL_DFRobot_FireBeetle2_ESP32S3 // Has PSRAM
//#define CAMERA_MODEL_DFRobot_Romeo_ESP32S3 // Has PSRAM
#include "camera_pins.h"
// ===========================
// Enter your WiFi credentials
// ===========================
const char* ssid = "sparkleiot";
const char* password = "12345678";
void startCameraServer();
void setupLedFlash(int pin);
void setup() {
Serial.begin(115200);
Serial.setDebugOutput(true);
Serial.println();
camera_config_t config;
config.ledc_channel = LEDC_CHANNEL_0;
config.ledc_timer = LEDC_TIMER_0;
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_sccb_sda = SIOD_GPIO_NUM;
config.pin_sccb_scl = SIOC_GPIO_NUM;
config.pin_pwdn = PWDN_GPIO_NUM;
config.pin_reset = RESET_GPIO_NUM;
config.xclk_freq_hz = 20000000;
config.frame_size = FRAMESIZE_QVGA;
//config.pixel_format = PIXFORMAT_JPEG; // for streaming
config.pixel_format = PIXFORMAT_RGB565; // for face detection/recognition
config.grab_mode = CAMERA_GRAB_WHEN_EMPTY;
config.fb_location = CAMERA_FB_IN_PSRAM;
config.jpeg_quality = 12;
config.fb_count = 1;
// if PSRAM IC present, init with UXGA resolution and higher JPEG quality
// for larger pre-allocated frame buffer.
if(config.pixel_format == PIXFORMAT_JPEG){
if(psramFound()){
config.jpeg_quality = 10;
config.fb_count = 2;
config.grab_mode = CAMERA_GRAB_LATEST;
} else {
// Limit the frame size when PSRAM is not available
config.frame_size = FRAMESIZE_SVGA;
config.fb_location = CAMERA_FB_IN_DRAM;
}
} else {
// Best option for face detection/recognition
config.frame_size = FRAMESIZE_QVGA;
#if CONFIG_IDF_TARGET_ESP32S3
config.fb_count = 2;
#endif
}
#if defined(CAMERA_MODEL_ESP_EYE)
pinMode(13, INPUT_PULLUP);
pinMode(14, INPUT_PULLUP);
#endif
// 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;
}
sensor_t * s = esp_camera_sensor_get();
// initial sensors are flipped vertically and colors are a bit saturated
if (s->id.PID == OV3660_PID) {
s->set_vflip(s, 1); // flip it back
s->set_brightness(s, 1); // up the brightness just a bit
s->set_saturation(s, -2); // lower the saturation
}
// drop down frame size for higher initial frame rate
if(config.pixel_format == PIXFORMAT_JPEG){
s->set_framesize(s, FRAMESIZE_QVGA);
}
#if defined(CAMERA_MODEL_M5STACK_WIDE) || defined(CAMERA_MODEL_M5STACK_ESP32CAM)
s->set_vflip(s, 1);
s->set_hmirror(s, 1);
#endif
#if defined(CAMERA_MODEL_ESP32S3_EYE)
s->set_vflip(s, 1);
#endif
// Setup LED FLash if LED pin is defined in camera_pins.h
#if defined(LED_GPIO_NUM)
setupLedFlash(LED_GPIO_NUM);
#endif
Serial.println("The device needs to be linked to a 2.4G router........");
Serial.println("SSSID:sparkleiot");
Serial.println("Password:12345678");
WiFi.begin(ssid, password);
WiFi.setSleep(false);
while (WiFi.status() != WL_CONNECTED) {
delay(500);
Serial.print(".");
}
Serial.println("");
Serial.println("WiFi connected");
startCameraServer();
Serial.print("Camera Ready! Use 'http://");
Serial.print(WiFi.localIP());
Serial.println("' to connect");
}
void loop() {
// Do nothing. Everything is done in another task by the web server
delay(10000);
}

View File

@ -1,318 +0,0 @@
#if defined(CAMERA_MODEL_WROVER_KIT)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM -1
#define XCLK_GPIO_NUM 21
#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 19
#define Y4_GPIO_NUM 18
#define Y3_GPIO_NUM 5
#define Y2_GPIO_NUM 4
#define VSYNC_GPIO_NUM 25
#define HREF_GPIO_NUM 23
#define PCLK_GPIO_NUM 22
#elif defined(CAMERA_MODEL_ESP_EYE)
#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
// 4 for flash led or 33 for normal led
#define LED_GPIO_NUM 4
#elif defined(CAMERA_MODEL_M5STACK_PSRAM)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM 15
#define XCLK_GPIO_NUM 27
#define SIOD_GPIO_NUM 25
#define SIOC_GPIO_NUM 23
#define Y9_GPIO_NUM 19
#define Y8_GPIO_NUM 36
#define Y7_GPIO_NUM 18
#define Y6_GPIO_NUM 39
#define Y5_GPIO_NUM 5
#define Y4_GPIO_NUM 34
#define Y3_GPIO_NUM 35
#define Y2_GPIO_NUM 32
#define VSYNC_GPIO_NUM 22
#define HREF_GPIO_NUM 26
#define PCLK_GPIO_NUM 21
#elif defined(CAMERA_MODEL_M5STACK_V2_PSRAM)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM 15
#define XCLK_GPIO_NUM 27
#define SIOD_GPIO_NUM 22
#define SIOC_GPIO_NUM 23
#define Y9_GPIO_NUM 19
#define Y8_GPIO_NUM 36
#define Y7_GPIO_NUM 18
#define Y6_GPIO_NUM 39
#define Y5_GPIO_NUM 5
#define Y4_GPIO_NUM 34
#define Y3_GPIO_NUM 35
#define Y2_GPIO_NUM 32
#define VSYNC_GPIO_NUM 25
#define HREF_GPIO_NUM 26
#define PCLK_GPIO_NUM 21
#elif defined(CAMERA_MODEL_M5STACK_WIDE)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM 15
#define XCLK_GPIO_NUM 27
#define SIOD_GPIO_NUM 22
#define SIOC_GPIO_NUM 23
#define Y9_GPIO_NUM 19
#define Y8_GPIO_NUM 36
#define Y7_GPIO_NUM 18
#define Y6_GPIO_NUM 39
#define Y5_GPIO_NUM 5
#define Y4_GPIO_NUM 34
#define Y3_GPIO_NUM 35
#define Y2_GPIO_NUM 32
#define VSYNC_GPIO_NUM 25
#define HREF_GPIO_NUM 26
#define PCLK_GPIO_NUM 21
#define LED_GPIO_NUM 2
#elif defined(CAMERA_MODEL_M5STACK_ESP32CAM)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM 15
#define XCLK_GPIO_NUM 27
#define SIOD_GPIO_NUM 25
#define SIOC_GPIO_NUM 23
#define Y9_GPIO_NUM 19
#define Y8_GPIO_NUM 36
#define Y7_GPIO_NUM 18
#define Y6_GPIO_NUM 39
#define Y5_GPIO_NUM 5
#define Y4_GPIO_NUM 34
#define Y3_GPIO_NUM 35
#define Y2_GPIO_NUM 17
#define VSYNC_GPIO_NUM 22
#define HREF_GPIO_NUM 26
#define PCLK_GPIO_NUM 21
#elif defined(CAMERA_MODEL_M5STACK_UNITCAM)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM 15
#define XCLK_GPIO_NUM 27
#define SIOD_GPIO_NUM 25
#define SIOC_GPIO_NUM 23
#define Y9_GPIO_NUM 19
#define Y8_GPIO_NUM 36
#define Y7_GPIO_NUM 18
#define Y6_GPIO_NUM 39
#define Y5_GPIO_NUM 5
#define Y4_GPIO_NUM 34
#define Y3_GPIO_NUM 35
#define Y2_GPIO_NUM 32
#define VSYNC_GPIO_NUM 22
#define HREF_GPIO_NUM 26
#define PCLK_GPIO_NUM 21
#elif defined(CAMERA_MODEL_AI_THINKER)
#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
// 4 for flash led or 33 for normal led
#define LED_GPIO_NUM 4
#elif defined(CAMERA_MODEL_TTGO_T_JOURNAL)
#define PWDN_GPIO_NUM 0
#define RESET_GPIO_NUM 15
#define XCLK_GPIO_NUM 27
#define SIOD_GPIO_NUM 25
#define SIOC_GPIO_NUM 23
#define Y9_GPIO_NUM 19
#define Y8_GPIO_NUM 36
#define Y7_GPIO_NUM 18
#define Y6_GPIO_NUM 39
#define Y5_GPIO_NUM 5
#define Y4_GPIO_NUM 34
#define Y3_GPIO_NUM 35
#define Y2_GPIO_NUM 17
#define VSYNC_GPIO_NUM 22
#define HREF_GPIO_NUM 26
#define PCLK_GPIO_NUM 21
#elif defined(CAMERA_MODEL_XIAO_ESP32S3)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM -1
#define XCLK_GPIO_NUM 10
#define SIOD_GPIO_NUM 40
#define SIOC_GPIO_NUM 39
#define Y9_GPIO_NUM 48
#define Y8_GPIO_NUM 11
#define Y7_GPIO_NUM 12
#define Y6_GPIO_NUM 14
#define Y5_GPIO_NUM 16
#define Y4_GPIO_NUM 18
#define Y3_GPIO_NUM 17
#define Y2_GPIO_NUM 15
#define VSYNC_GPIO_NUM 38
#define HREF_GPIO_NUM 47
#define PCLK_GPIO_NUM 13
#elif defined(CAMERA_MODEL_ESP32_CAM_BOARD)
// The 18 pin header on the board has Y5 and Y3 swapped
#define USE_BOARD_HEADER 0
#define PWDN_GPIO_NUM 32
#define RESET_GPIO_NUM 33
#define XCLK_GPIO_NUM 4
#define SIOD_GPIO_NUM 18
#define SIOC_GPIO_NUM 23
#define Y9_GPIO_NUM 36
#define Y8_GPIO_NUM 19
#define Y7_GPIO_NUM 21
#define Y6_GPIO_NUM 39
#if USE_BOARD_HEADER
#define Y5_GPIO_NUM 13
#else
#define Y5_GPIO_NUM 35
#endif
#define Y4_GPIO_NUM 14
#if USE_BOARD_HEADER
#define Y3_GPIO_NUM 35
#else
#define Y3_GPIO_NUM 13
#endif
#define Y2_GPIO_NUM 34
#define VSYNC_GPIO_NUM 5
#define HREF_GPIO_NUM 27
#define PCLK_GPIO_NUM 25
#elif defined(CAMERA_MODEL_ESP32S3_CAM_LCD)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM -1
#define XCLK_GPIO_NUM 40
#define SIOD_GPIO_NUM 17
#define SIOC_GPIO_NUM 18
#define Y9_GPIO_NUM 39
#define Y8_GPIO_NUM 41
#define Y7_GPIO_NUM 42
#define Y6_GPIO_NUM 12
#define Y5_GPIO_NUM 3
#define Y4_GPIO_NUM 14
#define Y3_GPIO_NUM 47
#define Y2_GPIO_NUM 13
#define VSYNC_GPIO_NUM 21
#define HREF_GPIO_NUM 38
#define PCLK_GPIO_NUM 11
#elif defined(CAMERA_MODEL_ESP32S2_CAM_BOARD)
// The 18 pin header on the board has Y5 and Y3 swapped
#define USE_BOARD_HEADER 0
#define PWDN_GPIO_NUM 1
#define RESET_GPIO_NUM 2
#define XCLK_GPIO_NUM 42
#define SIOD_GPIO_NUM 41
#define SIOC_GPIO_NUM 18
#define Y9_GPIO_NUM 16
#define Y8_GPIO_NUM 39
#define Y7_GPIO_NUM 40
#define Y6_GPIO_NUM 15
#if USE_BOARD_HEADER
#define Y5_GPIO_NUM 12
#else
#define Y5_GPIO_NUM 13
#endif
#define Y4_GPIO_NUM 5
#if USE_BOARD_HEADER
#define Y3_GPIO_NUM 13
#else
#define Y3_GPIO_NUM 12
#endif
#define Y2_GPIO_NUM 14
#define VSYNC_GPIO_NUM 38
#define HREF_GPIO_NUM 4
#define PCLK_GPIO_NUM 3
#elif defined(CAMERA_MODEL_ESP32S3_EYE)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM -1
#define XCLK_GPIO_NUM 15
#define SIOD_GPIO_NUM 4
#define SIOC_GPIO_NUM 5
#define Y2_GPIO_NUM 11
#define Y3_GPIO_NUM 9
#define Y4_GPIO_NUM 8
#define Y5_GPIO_NUM 10
#define Y6_GPIO_NUM 12
#define Y7_GPIO_NUM 18
#define Y8_GPIO_NUM 17
#define Y9_GPIO_NUM 16
#define VSYNC_GPIO_NUM 6
#define HREF_GPIO_NUM 7
#define PCLK_GPIO_NUM 13
#elif defined(CAMERA_MODEL_DFRobot_FireBeetle2_ESP32S3) || defined(CAMERA_MODEL_DFRobot_Romeo_ESP32S3)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM -1
#define XCLK_GPIO_NUM 45
#define SIOD_GPIO_NUM 1
#define SIOC_GPIO_NUM 2
#define Y9_GPIO_NUM 48
#define Y8_GPIO_NUM 46
#define Y7_GPIO_NUM 8
#define Y6_GPIO_NUM 7
#define Y5_GPIO_NUM 4
#define Y4_GPIO_NUM 41
#define Y3_GPIO_NUM 40
#define Y2_GPIO_NUM 39
#define VSYNC_GPIO_NUM 6
#define HREF_GPIO_NUM 42
#define PCLK_GPIO_NUM 5
#else
#error "Camera model not selected"
#endif

View File

@ -1,5 +0,0 @@
# Name, Type, SubType, Offset, Size, Flags
nvs, data, nvs, 0x9000, 0x5000,
otadata, data, ota, 0xe000, 0x2000,
app0, app, ota_0, 0x10000, 0x3d0000,
fr, data, , 0x3e0000, 0x20000,
1 # Name Type SubType Offset Size Flags
2 nvs data nvs 0x9000 0x5000
3 otadata data ota 0xe000 0x2000
4 app0 app ota_0 0x10000 0x3d0000
5 fr data 0x3e0000 0x20000

Binary file not shown.

Binary file not shown.

Before

Width:  |  Height:  |  Size: 60 KiB

View File

@ -1,200 +0,0 @@
# ESP32-S3-CAM
What we need for functionality
- ESP32-S3-CAM board with OV2640 camera module [ here ](#esp32)
- Supported camera modules [here](#cam_modules)
- Module board version [here](#different_mcu)
- How to flash binary files to board from Linux/MAC/Windows [ here ](#flash_fw)
- How to compile software in the Arduino IDE [ here ](#arduino_cfg)
- How to reset the configuration to factory settings [here](#factory_cfg)
- Status LED [ here ](#status_led)
- Schematic main board is [here](#schematic)
- External FLASH LED [here](#led_issue)
- Power supply [here](#power_supply)
- External temperature sensor DHT22/DHT11 [here](#ext_sens)
- Potential issue [here](#issue)
<a name="esp32"></a>
## ESP32-S3-CAM
Basic information:
- Onboard RGB LED (most likely ws2812b)
- Option connecting external FLASH LED
- Micro SD card slot
- Internal or External WiFi antenna
- 16MB FLASH and 8MB external PSRAM
- 520 KB SRAM
- Excellent WiFi signal
- There is no official documentation for this module.
- Additional HW must be purchased for programming
This is a module with an ESP32-S3 processor. It is a dimensional copy of the ESP32-CAM board by AiThinker. The board has the same dimensions but features a more powerful ESP32-S3 processor and an RGB LED for illumination. The LED for illumination is likely of the WS2812B type. There is no official documentation or circuit diagram available for this board. The camera module consists of two boards: the main board with the WiFi MCU, camera, micro SD card slot, and LED for illumination, and a second board used for programming that has a micro USB connector. Board pineout it's not same as on the AiThinker ESP32-CAM.
<img src="board2.png" width=30% height=30%>
<a name="cam_modules"></a>
## Supported camera modules
It's necessary to use a camera version **OV2640**. If using a different camera, modification of the camera's pinout can be needed, or some camera settings may not work correctly. We recommend to use a camera module with a viewing angle of 120° or 160°.
These are currently known or tested camera modules:
| Camera chip | FOV | Resolution | Tested | Works | Description |
|-------------|------|------------|--------|-------|------------------------------------------|
| OV2640 | 66° | 2MP | Yes | Yes | Recommended. Standard camera module |
| OV2640 | 120° | 2MP | Yes | Yes | Recommended |
| OV2640 | 160° | 2MP | Yes | Yes | Recommended |
<a name="flash_fw"></a>
## How to flash binary files to board from Linux/MAC/Windows
#### Partitions table for flashing FW
However, for uploading the firmware, it's important to use this configuration of addresses and files:
ZIP file with build binary files: **esp32-s3-cam.zip**
- address 0x0 - ESP32_PrusaConnectCam.ino.bootloader.bin
- address 0x8000 - ESP32_PrusaConnectCam.ino.partitions.bin
- address 0x10000 - ESP32_PrusaConnectCam.ino.bin
**It is important to download the correct binary files! Each type of camera has its own ZIP archive with files for uploading the firmware.**
#### Linux/MAC
You must use the console to upload the firmware on the MAC or Linux platform. First, ensure you have installed esptool for Python. You can find it on the manufacturer's website, ESPRESSIF, [here](https://docs.espressif.com/projects/esp-at/en/latest/esp32/Get_Started/Downloading_guide.html#linux-or-macos).
And command for FLASH FW is here, where **/dev/ttya0** is your serial interface for communication with the ESP32-cam board. This is the command for the first flash FW to MCU.
```
./esptool --chip esp32s3 -p /dev/ttya0 -b 921600 --before default_reset --after hard_reset write_flash --erase-all --flash_mode dio --flash_size 16MB --flash_freq 80m 0x0 ESP32_PrusaConnectCam.ino.bootloader.bin 0x8000 ESP32_PrusaConnectCam.ino.partitions.bin 0x10000 ESP32_PrusaConnectCam.ino.bin
```
This command contains the parameter **--erase-all**, which erases the entire flash in the MCU. So, for just updating the firmware, it is necessary to remove the parameter **--erase-all**; otherwise, the MCU configuration will also be deleted. The basic command list can be found [here](https://docs.espressif.com/projects/esptool/en/latest/esp32s3/esptool/basic-commands.html)
Here is the command for updating the firmware in the MCU without erasing the MCU configuration
```
./esptool --chip esp32s3 -p /dev/ttya0 -b 921600 --before default_reset --after hard_reset write_flash --flash_mode dio --flash_size 16MB --flash_freq 80m 0x0 ESP32_PrusaConnectCam.ino.bootloader.bin 0x8000 ESP32_PrusaConnectCam.ino.partitions.bin 0x10000 ESP32_PrusaConnectCam.ino.bin
```
Launching the esptool application may be different in different operating systems
#### Windows
The driver should be installed automatically by Windows. SW for FW flash (Flash Download Tools) is [here](https://www.espressif.com/en/support/download/other-tools)
In the first step, you need to open the application **flash download tool**, and select MCU version
<img src="chip_select.jpg" width=25% height=25%>
Then, select the communication port. It's necessary to erase the FLASH using the **ERASE** button before the first firmware flash.
<img src="fw_flash.jpg" width=30% height=30%>
<a name="arduino_cfg"></a>
## How to compile software in the Arduino IDE
Board configuration in the Arduino IDE 2.3.2
- Tools -> Board -> ESP32 Arduino -> ESP32S3 Dev Module
- Tools -> USB CDC on BOOT -> Disable
- Tools -> CPU Frequency -> 240MHz (WiFi/BT)
- Tools -> Core debug level -> None
- Tools -> USB DFU on BOOT -> Disable
- Tools -> Erase all Flash Before Sketch Upload -> Disable (first flash, new board = enable. otherwise = disable)
- Tools -> Events Run On -> Core 1
- Tools -> Flash Mode -> DIO 80MHz
- Tools -> Flash Size -> 16MB
- Tools -> Jtag Adapter -> Disable
- Tools -> Arduino Runs On -> Core 1
- Tools -> USB Firmware MSC On Boot -> Disable
- Tools -> Partition scheme -> Minimal SPIFFS (1.9MB APP with OTA/190KB SPIFFS)
- Tools -> PSRAM -> OPI PSRAM
- Tools -> Upload Mode -> UART0 / Hardware CDC
- Tools -> Upload Speed -> 921600
- Tools -> USB Mode -> Hardware CDC and JTAG
- Tools -> Zigbee mode -> Disable
When flashing the firmware to a new, empty ESP32-S3-CAM Sense device for the first time, it is necessary to use the 'Erase' function.
This can be found under **Tools** -> **Erase all Flash Before Sketch Upload** -> **Enable**.
After the initial firmware upload to the MCU, it's necessary to disable this option. If you do not disable this option, your camera configuration will continue to be erased from the flash memory after uploading new firmware from the Arduino IDE.
It is necessary to enable support for the correct board version in the file **mcu_cfg.h** after line 16.
<a name="factory_cfg"></a>
## How to reset configuration to factory settings
To reset the settings to factory defaults, follow these instructions:
<img src="sw_reset.png" width=30% height=30%>
- Connect PIN **GPIO14** to **ground**.
- **Plug in** the power supply.
- Wait for **10 seconds**.
- After 10 seconds, the **FLASH LED will start flashing**.
- **Disconnect** PIN **GPIO14** from **ground** (but don't disconnect the power supply).
- After disconnecting **GPIO14** from **ground**, the **FLASH LED** will **stop flashing**, and the MCU will **automatically reboot**.
- Now the MCU is in the factory settings.
<a name="status_led"></a>
## Status LED
On the board, there is a status LED that provides a visual indicator of the module's current status
through blinking at defined intervals.
<img src="status_led.png" width=25% height=25%>
Upon module activation, the LED illuminates. After processor initialization, the LED exhibits different blinking intervals based on the current mode of the module
- **Service AP Mode only:** The LED blinks every **400 ms**, indicating the module's availability in service AP mode.
- **Connecting to WiFi AP:** While connecting to a WiFi Access Point, the LED blinks at intervals of **800 ms**.
- **Connected to WiFi Network:** Upon successful connection to a WiFi network, the LED blinks at intervals of **4000 ms**, signaling a stable connection.
- **Problematic State:** If an issue or error occurs, the LED accelerates its blinking to every **100 ms**.
The approximate boot time of the device is 15-20 seconds.
<a name="schematic"></a>
## Schematic for ESP32-S3-CAM
For this board, I was unable to find any official documentation or pinout. The following pinout was determined from PCB analysis.
Pinout
<img src="pinout.drawio.png" width=50% height=50%>
<a name="led_issue"></a>
## FLASH LED
This board version have RGB **FLASH LED** on the board (most likely ws2812b). It is still possible to connect an external LED for illumination. The wiring is shown in the image below.
<img src="relay_flash_bb.png" width=30% height=30%>
For the external LED is in the SW used **GPIO pin 47**.
<img src="ext_led_pins.png" width=30% height=30%>
However, a 5mm LED can also be connected directly. **CAUTION**: The digital GPIO output from the ESP32-S3-CAM board has a current limitation of a **maximum of 40mA**! Therefore, it is recommended to switch the LED using a **transistor** rather than directly through the GPIO pin. Improper use of the GPIO pin can lead to permanent damage.
<a name="power_supply"></a>
## Power Supply
The device requires a 5V power supply, with a maximum current consumption of 2A. Power is supplied via a micro USB connector when using the original programmer.
<a name="ext_sens"></a>
## External temperature sensor DHT22/DHT11
Below you will find the wiring diagram for the DHT22 or DHT11 sensor.
| Camera board | DHT22/DHT11 |
|--------------|-------------|
| 3.3V | VCC |
| GND | GND |
| GPIO20 | Data |
<img src="ESP32-cam dht22_bb.png" width=40% height=40%>
<a name="issue"></a>
## Potential issue with this board
- Slow WEB page loading during first 1 minutes after MCU start

Binary file not shown.

Before

Width:  |  Height:  |  Size: 86 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 47 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 538 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 675 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 297 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 9.2 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 524 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 81 KiB

View File

@ -1,116 +0,0 @@
ESP-ROM:esp32s3-20210327
Build:Mar 27 2021
rst:0x1 (POWERON),boot:0x2a (SPI_FAST_FLASH_BOOT)
SPIWP:0xee
mode:DIO, clock div:1
load:0x3fcd0108,len:0x15c8
load:0x403b6000,len:0x8c8
load:0x403ba000,len:0x2c04
entry 0x403b61c4
I (25) boot: ESP-IDF v4.4-dev-2594-ga20df743f1-dirty 2nd stage bootloader
I (25) boot: compile time 16:57:21
I (25) boot: chip revision: 0
I (29) boot.esp32s3: SPI Speed : 80MHz
I (33) boot.esp32s3: SPI Mode : DIO
I (38) boot.esp32s3: SPI Flash Size : 2MB
I (43) boot: Enabling RNG early entropy source...
W (48) bootloader_random: RNG for ESP32-S3 not currently supported
I (55) boot: Partition Table:
I (59) boot: ## Label Usage Type ST Offset Length
I (66) boot: 0 nvs WiFi data 01 02 00009000 00006000
I (73) boot: 1 phy_init RF data 01 01 0000f000 00001000
I (81) boot: 2 factory factory app 00 00 00010000 00100000
I (88) boot: End of partition table
I (93) esp_image: segment 0: paddr=00010020 vaddr=3c020020 size=090e0h ( 37088) map
I (108) esp_image: segment 1: paddr=00019108 vaddr=3fc90dd0 size=0253ch ( 9532) load
I (111) esp_image: segment 2: paddr=0001b64c vaddr=40374000 size=049cch ( 18892) load
I (122) esp_image: segment 3: paddr=00020020 vaddr=42000020 size=1b660h (112224) map
I (147) esp_image: segment 4: paddr=0003b688 vaddr=403789cc size=08404h ( 33796) load
I (155) esp_image: segment 5: paddr=00043a94 vaddr=50000000 size=00010h ( 16) load
I (160) boot: Loaded app from partition at offset 0x10000
I (160) boot: Disabling RNG early entropy source...
W (164) bootloader_random: RNG for ESP32-S3 not currently supported
I (182) cpu_start: Pro cpu up.
I (182) cpu_start: Starting app cpu, entry point is 0x40375104
I (0) cpu_start: App cpu up.
I (196) cpu_start: Pro cpu start user code
I (196) cpu_start: cpu freq: 160000000
[0;32mI (199) cpu_start: Project name: led_strip
I (204) cpu_start: App version: 1
I (209) cpu_start: Compile time: Aug 17 2021 17:09:47
I (215) cpu_start: ELF file SHA256: bda59acbde3f7a0e...
I (221) cpu_start: ESP-IDF: v4.4-dev-2594-ga20df743f1-dirty
I (228) heap_init: Initializing. RAM available for dynamic allocation:
I (235) heap_init: At 3FC94220 len 0004BDE0 (303 KiB): D/IRAM
I (241) heap_init: At 3FCE0000 len 0000EE34 (59 KiB): STACK/DRAM
I (248) heap_init: At 3FCF0000 len 00008000 (32 KiB): DRAM
I (255) spi_flash: detected chip: generic
I (259) spi_flash: flash io: dio
W (263) spi_flash: Detected size(16384k) larger than the size in the binary image header(2048k). Using the size in the binary image header.
I (277) cpu_start: Starting scheduler on PRO CPU.
I (0) cpu_start: Starting scheduler on APP CPU.
I (308) example: LED Rainbow Chase Start
I (308) example: USB initialization
I (308) tusb_desc:
┌─────────────────────────────────┐
│ USB Device Descriptor Summary │
├───────────────────┬─────────────┤
│bDeviceClass │ 239 │
├───────────────────┼─────────────┤
│bDeviceSubClass │ 2 │
├───────────────────┼─────────────┤
│bDeviceProtocol │ 1 │
├───────────────────┼─────────────┤
│bMaxPacketSize0 │ 64 │
├───────────────────┼─────────────┤
│idVendor │ 0x303a │
├───────────────────┼─────────────┤
│idProduct │ 0x4001 │
├───────────────────┼─────────────┤
│bcdDevice │ 0x100 │
├───────────────────┼─────────────┤
│iManufacturer │ 0x1 │
├───────────────────┼─────────────┤
│iProduct │ 0x2 │
├───────────────────┼─────────────┤
│iSerialNumber │ 0x3 │
├───────────────────┼─────────────┤
│bNumConfigurations │ 0x1 │
└───────────────────┴─────────────┘
I (478) TinyUSB: TinyUSB Driver installed
I (488) example: USB initialization DONE
I (1388) example: log -> UART
example: print -> stdout
example: print -> stderr
I (2888) example: log -> UART
example: print -> stdout
example: print -> stderr
I (4388) example: log -> UART
example: print -> stdout
example: print -> stderr
I (5888) example: log -> UART
example: print -> stdout
example: print -> stderr
I (7388) example: log -> UART
example: print -> stdout
example: print -> stderr
I (8888) example: log -> UART
example: print -> stdout
example: print -> stderr
I (10388) example: log -> UART
example: print -> stdout
example: print -> stderr
I (11888) example: log -> UART
example: print -> stdout
example: print -> stderr
I (13388) example: log -> UART
example: print -> stdout
example: print -> stderr
I (14888) example: log -> UART
example: print -> stdout
example: print -> stderr
I (16388) example: log -> UART
example: print -> stdout
example: print -> stderr
I (17888) example: log -> UART
example: print -> stdout

File diff suppressed because one or more lines are too long

Binary file not shown.

Before

Width:  |  Height:  |  Size: 1.1 MiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 704 KiB

Binary file not shown.

Binary file not shown.

Before

Width:  |  Height:  |  Size: 117 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 512 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 520 KiB

Some files were not shown because too many files have changed in this diff Show More