mirror of
https://github.com/jomjol/AI-on-the-edge-device.git
synced 2025-12-17 13:08:40 +03:00
Prepare next release (#3267)
* Create dig-cont_0640_s3_q.tflite * Update edit_reference.html (#2924) Zoom-Einstellungen ausblenden, wenn zoom deaktiviert ist * Update edit_config_template.html (#2925) Zoom-Einstellungen ausblenden, wenn zoom deaktiviert ist + Kameraeinstellungen nicht nur in der config.ini speichern, sondern auch setzen * The parameter "negative" is processed on the MCU * Renamed menu entry Alignment -> References * renamed model file to make naming consistent * Fix test (#2933) * always reset change absolute (#2956) * Create dig-class11_1701_s2.tflite * Update tflite * Update tflite * Camera settings (#3029) * Add files via upload * Add files via upload * Add files via upload * Add files via upload * Add files via upload * Add files via upload * Add files via upload * Add files via upload * Fix minor typo and harmonize spaces (#3030) * Update edit_digits.html * Update edit_analog.html * Update overview.html * Update edit_reference.html --------- Co-authored-by: jomjol <30766535+jomjol@users.noreply.github.com> * Source code formatting, ClassFlowPostProcessing.cpp * fix edit_config_template.html Unfortunately, I didn't take out some entries from other experiments because I overlooked/forgot them^^ * fix readconfigparam.js Unfortunately, I didn't take out some entries from other experiments because I overlooked/forgot them^^ * fix edit_config_template.html TakeImage_CamZoomMode_value1 was replaced by TakeImage_CamZoomSize_value1, but not deleted. This caused problems when saving the camera settings. * Update info.html function loadWLANSSID() was present three times * Update overview.html CamFrameSize is no longer needed/used for zoom * Update reply-bot.yaml * homeassistant service discovery: derive node_id when using nested topics (#3088) * derive correct node_id for homeassistant service discovery in nested topics (fixes #1792) * explicit use of std::string * move nodeId creation to separate function add unit-tests * add documentation about node_id generation for Home Assistant MQTT Service Discovery * add Prometheus/OpenMetrics exporter (#3081) * add prometheus endpoint * refine metrics implementation * move metrics generator to ClassFlowControll * add more metrics align prefix * add more metrics clean up * refine documentation * revert dependencies change * sanitize labels * create separate module for openmetrics * move openmetrics to separate folder * clean up * add basic unit-tests * work with const numbers add replaceAll for string replacement avoid opening std namespace adapt unit-tests * Update code/main/server_main.cpp --------- Co-authored-by: CaCO3 <caco3@ruinelli.ch> * Typo * update platformIO to 6.7.0 (ESP IDF 5.2.1) (#3098) * update to platformio/espressif32 @ 6.7.0 * remove unused getReadout() as it throws errors (error: 'virtual std::string ClassFlow::getReadout()' was hidden). --------- Co-authored-by: CaCO3 <caco@ruinelli.ch> * Update reply-bot.yaml (#3107) * Fix actions-label-commenter * Update Helper.cpp * Update Helper.h * Update Helper.cpp * Update readconfigparam.js fix for: In the selected field the value '1' in the section 'TakeImage' in the field 'CamGainceiling' is invalid. PLEASE CHECK BEFORE SAVING! * proposal for renaming and documentation (#3115) * Update server_camera.cpp Fix building with -D DEBUG_DETAIL_ON better alternative to: https://github.com/jomjol/AI-on-the-edge-device/pull/3160 * Update ClassFlowPostProcessing.cpp * Update ClassFlowAlignment.cpp * Fix building with `-D DEBUG_DETAIL_ON` (#3160) Building with `-D DEBUG_DETAIL_ON` has been broken since #3029. Co-authored-by: CaCO3 <caco3@ruinelli.ch> * Handle empty prevalue.ini gracefully (#3162) Fixes #2149. * Bugfix for boot loop (#3175) * Add files via upload * Add files via upload * Add files via upload * Delete param-docs/parameter-pages/TakeImage/Aec2.md has been replaced by CamAec2.md * Delete param-docs/parameter-pages/TakeImage/AutoExposureLevel.md has been replaced by CamAeLevel.md * Delete param-docs/parameter-pages/TakeImage/Brightness.md has been replaced by CamBrightness.md * Delete param-docs/parameter-pages/TakeImage/Contrast.md has been replaced by CamContrast.md * Delete param-docs/parameter-pages/TakeImage/Grayscale.md has been replaced by CamSpecialEffect.md * Delete param-docs/parameter-pages/TakeImage/Negative.md has been replaced by CamSpecialEffect.md * Delete param-docs/parameter-pages/TakeImage/Saturation.md has been replaced by CamSaturation.md * Delete param-docs/parameter-pages/TakeImage/Sharpness.md has been replaced by CamSharpness.md * Delete param-docs/parameter-pages/TakeImage/ImageQuality.md has been replaced by CamQuality.md * Delete param-docs/parameter-pages/TakeImage/Zoom.md has been replaced by CamZoom.md * Delete param-docs/parameter-pages/TakeImage/ZoomMode.md has been replaced by CamZoomSize.md * Delete param-docs/parameter-pages/TakeImage/ZoomOffsetX.md has been replaced by CamZoomOffsetX.md * Delete param-docs/parameter-pages/TakeImage/ZoomOffsetY.md has been replaced by CamZoomOffsetY.md * Delete param-docs/parameter-pages/TakeImage/ImageSize.md has been replaced by CamZoomSize.md * Delete param-docs/parameter-pages/TakeImage/FixedExposure.md has been replaced by CamAec.md * Delete param-docs/parameter-pages/Alignment/FlipImageSize.md has been replaced by CamVflip.md * Delete param-docs/parameter-pages/Alignment/InitialMirror.md has been replaced by CamHmirror.md * CamParameter documentation update https://github.com/jomjol/AI-on-the-edge-device/issues/3185 * typo * add Webhook #3148 (#3163) * WIP add Webhook * fix config html for webhook add tooltips for webhook * webhook: fix not enabling webhook * send webhook as json * Update ApiKey.md * webhook: fix only sending last "Number" * webhook JSON is now closer to the data log in CSV format * webhook: drop timeStampTimeUTC and switch from timeStamp to lastvalue like lokal csv to fix no timestamp on error --------- Co-authored-by: CaCO3 <caco3@ruinelli.ch> * Bugfix for time stamp (#3180) * Update ClassFlowPostProcessing.cpp * Update ClassFlowDefineTypes.h * Update ClassFlowPostProcessing.cpp * Update ClassFlowPostProcessing.cpp * Update ClassFlowPostProcessing.cpp * Update ClassFlowPostProcessing.cpp * Update interface_webhook.cpp * Update readconfigcommon.js fix for: The same message("Image Contrast got enhanced") came up with "Update Marker" and "Enhance Image Contrast". * fix svg favicon The svg one got added in33893eb566but does not work on Firefox * Update platformIO to 6.8.1 (Contains ESP IDF 5.3) (#3196) * Update platformIO to 6.8.1 (ESP IDF 5.3) * removed now redundant typedef * updated IDF manifest hash * Add files via upload so it should work now * Update server_main.cpp --------- Co-authored-by: CaCO3 <caco@ruinelli.ch> Co-authored-by: michael <Heinrich-Tuning@web.de> * Update MainFlowControl.cpp * Add support for OV5640 camera (#3063) * Add support for OV5640 camera * clean up sharpness handling * limit sharpness range to -2 and +2 * refactor * Fix OV3660 sharpness handling * refactor sharpness handling * fix OV3660 zoom mode * reinstate aspect ratio via imageSize * Changed OV5640 full frame size to match datasheet * various fixes * add denoise config and general clean up * fix line endings to LF * Support enabling red blue swap via web interface * update jpeg quality limits * remove color swap config; color swap workaround dependent on vflip * fix missing commit * fix gain ceiling * Update cam vflip param page * fix typo: camdenoise, not camsdenoise * fix compile errors * Update MainFlowControl.cpp * Add rate threshold parameter (#3195) * still needs to be tested https://github.com/jomjol/AI-on-the-edge-device/issues/3143 * Update ClassFlowPostProcessing.cpp code formatting * Update ClassFlowDefineTypes.h code formatting * Update ClassFlowPostProcessing.h code formatting * Update edit_config_template.html * fix * Update config.ini * Update edit_config_template.html * Updated param doc * Rename parameters * Update edit_config_template.html * Update NUMBER.ChangeRateThreshold.md * Update NUMBER.ChangeRateThreshold.md --------- Co-authored-by: CaCO3 <caco3@ruinelli.ch> * Update main.cpp * Update config.ini Adjusted camera settings to make the image brighter. * Update readconfigparam.js Adjusted camera settings to make the image brighter. * add optional ImageUpload for Webhook (#3174) * WIP add Webhook * fix config html for webhook add tooltips for webhook * webhook: fix not enabling webhook * send webhook as json * Update ApiKey.md * webhook: fix only sending last "Number" * webhook JSON is now closer to the data log in CSV format * webhook: add img upload * webhoop added config for imgupload * webhook html fixes * webhook: drop timeStampTimeUTC and switch from timeStamp to lastvalue like lokal csv to fix no timestamp on error * add checkbox for Webhook_UploadImg * Update sd-card/html/edit_config_template.html * Update edit_config_template.html * Update edit_config_template.html * Update edit_config_template.html * added a long timestamp to both webhook requests --------- Co-authored-by: CaCO3 <caco3@ruinelli.ch> * Add files via upload (#3207) * Update ClassFlowPostProcessing.cpp deleted some unnecessary double entries RateType renamed to MaxRateType * Update ClassFlowDefineTypes.h RateType renamed to MaxRateType * Update text on recognition page * Update digital CNN * add a Delay between the WiFi reconnections (#3068) * add a Delay between the WiFi reconnections * log the delay between the WiFi reconnections move the delay after the log * cleanup * cleanup * cleanup * Update edit_alignment.html * cleanup * cleanup * Update platformIO to 6.9.0 (Contains ESP IDF 5.3.1) * Handle crash on corrupted model (#3220) * Upgrade esp-tflite-micro to 1.3.1 * Added log message to hint in case it crashes on loading a corrupted model --------- Co-authored-by: CaCO3 <caco@ruinelli.ch> * new dig-class100-173-s2-q on 23.800 images (#3257) * new dig-class100-173-s2-q on 23.800 images * platformio/espressif32 @ 6.8.1 for esp32cam-dev * Revert "platformio/espressif32 @ 6.8.1 for esp32cam-dev" This reverts commitcc9297d483. * not using platformio 6.1.16 * Revert "not using platformio 6.1.16" This reverts commitef18e4fae7. * moved number edit box styles into new file edit_style.css (#3262) changed input[type=number] from 60px to 3em, to show 3 digits with current font size. * added note about only TLS 1.2 is supported (#3213) * Renamed digital to digit (#3219) * renamed Digital to Digit * added param migration * Update .github/label-commenter-config.yaml * renamed AnalogDigitTransition* to AnalogToDigitTransition* --------- Co-authored-by: CaCO3 <caco@ruinelli.ch> * Update Changelog.md * Update Changelog.md --------- Co-authored-by: jomjol <30766535+jomjol@users.noreply.github.com> Co-authored-by: michael <Heinrich-Tuning@web.de> Co-authored-by: Frank Haverland <fspapaping@googlemail.com> Co-authored-by: kub3let <95883234+kub3let@users.noreply.github.com> Co-authored-by: Marco H <myxor@users.noreply.github.com> Co-authored-by: Henry Thasler <henrythasler@users.noreply.github.com> Co-authored-by: CaCO3 <caco@ruinelli.ch> Co-authored-by: Sebastian Lövdahl <slovdahl@hibox.fi> Co-authored-by: Raphael Hehl <raphael@rhehl.de> Co-authored-by: jasaw <jasaw@dius.com.au> Co-authored-by: Francesco Carnielli <hex7c0@gmail.com> Co-authored-by: kalwados <kalwados@gmx.de>
This commit is contained in:
File diff suppressed because it is too large
Load Diff
@@ -15,66 +15,99 @@
|
||||
#include "CImageBasis.h"
|
||||
#include "../../include/defines.h"
|
||||
|
||||
class CCamera {
|
||||
protected:
|
||||
int ActualQuality;
|
||||
framesize_t ActualResolution;
|
||||
int brightness, contrast, saturation, autoExposureLevel;
|
||||
bool isFixedExposure;
|
||||
int waitbeforepicture_org;
|
||||
int led_intensity = 4095;
|
||||
typedef struct
|
||||
{
|
||||
uint16_t CamSensor_id;
|
||||
|
||||
void ledc_init(void);
|
||||
bool CameraInitSuccessful = false;
|
||||
bool demoMode = false;
|
||||
framesize_t ImageFrameSize = FRAMESIZE_VGA; // 0 - 10
|
||||
gainceiling_t ImageGainceiling; // Image gain (GAINCEILING_x2, x4, x8, x16, x32, x64 or x128)
|
||||
|
||||
bool loadNextDemoImage(camera_fb_t *fb);
|
||||
long GetFileSize(std::string filename);
|
||||
int ImageQuality; // 0 - 63
|
||||
int ImageBrightness; // (-2 to 2) - set brightness
|
||||
int ImageContrast; //-2 - 2
|
||||
int ImageSaturation; //-2 - 2
|
||||
int ImageSharpness; //-2 - 2
|
||||
bool ImageAutoSharpness;
|
||||
int ImageSpecialEffect; // 0 - 6
|
||||
int ImageWbMode; // 0 to 4 - if awb_gain enabled (0 - Auto, 1 - Sunny, 2 - Cloudy, 3 - Office, 4 - Home)
|
||||
int ImageAwb; // white balance enable (0 or 1)
|
||||
int ImageAwbGain; // Auto White Balance enable (0 or 1)
|
||||
int ImageAec; // auto exposure off (1 or 0)
|
||||
int ImageAec2; // automatic exposure sensor (0 or 1)
|
||||
int ImageAeLevel; // auto exposure levels (-2 to 2)
|
||||
int ImageAecValue; // set exposure manually (0-1200)
|
||||
int ImageAgc; // auto gain off (1 or 0)
|
||||
int ImageAgcGain; // set gain manually (0 - 30)
|
||||
int ImageBpc; // black pixel correction
|
||||
int ImageWpc; // white pixel correction
|
||||
int ImageRawGma; // (1 or 0)
|
||||
int ImageLenc; // lens correction (1 or 0)
|
||||
int ImageHmirror; // (0 or 1) flip horizontally
|
||||
int ImageVflip; // Invert image (0 or 1)
|
||||
int ImageDcw; // downsize enable (1 or 0)
|
||||
|
||||
void SetCamWindow(sensor_t *s, int resolution, int xOffset, int yOffset, int xLength, int yLength);
|
||||
void SetImageWidthHeightFromResolution(framesize_t resol);
|
||||
int ImageDenoiseLevel; // The OV2640 does not support it, OV3660 and OV5640 (0 to 8)
|
||||
|
||||
public:
|
||||
int image_height, image_width;
|
||||
bool imageZoomEnabled = false;
|
||||
int imageZoomMode = 0;
|
||||
int imageZoomOffsetX = 0;
|
||||
int imageZoomOffsetY = 0;
|
||||
bool imageNegative = false;
|
||||
bool imageAec2 = false;
|
||||
bool imageAutoSharpness = false;
|
||||
int imageSharpnessLevel = 0;
|
||||
#ifdef GRAYSCALE_AS_DEFAULT
|
||||
bool imageGrayscale = true;
|
||||
#else
|
||||
bool imageGrayscale = false;
|
||||
#endif
|
||||
|
||||
CCamera();
|
||||
esp_err_t InitCam();
|
||||
int ImageWidth;
|
||||
int ImageHeight;
|
||||
|
||||
void LightOnOff(bool status);
|
||||
void LEDOnOff(bool status);
|
||||
esp_err_t CaptureToHTTP(httpd_req_t *req, int delay = 0);
|
||||
esp_err_t CaptureToStream(httpd_req_t *req, bool FlashlightOn);
|
||||
void SetQualitySize(int qual, framesize_t resol, bool zoomEnabled, int zoomMode, int zoomOffsetX, int zoomOffsetY);
|
||||
bool SetBrightnessContrastSaturation(int _brightness, int _contrast, int _saturation, int _autoExposureLevel, bool _grayscale, bool _negative, bool _aec2, int _sharpnessLevel);
|
||||
void SetZoom(bool zoomEnabled, int zoomMode, int zoomOffsetX, int zoomOffsetY);
|
||||
void GetCameraParameter(httpd_req_t *req, int &qual, framesize_t &resol, bool &zoomEnabled, int &zoomMode, int &zoomOffsetX, int &zoomOffsetY);
|
||||
void SetLEDIntensity(float _intrel);
|
||||
bool testCamera(void);
|
||||
void EnableAutoExposure(int flash_duration);
|
||||
bool getCameraInitSuccessful();
|
||||
void useDemoMode(void);
|
||||
|
||||
int ImageLedIntensity;
|
||||
|
||||
framesize_t TextToFramesize(const char * text);
|
||||
bool ImageZoomEnabled;
|
||||
int ImageZoomOffsetX;
|
||||
int ImageZoomOffsetY;
|
||||
int ImageZoomSize;
|
||||
|
||||
esp_err_t CaptureToFile(std::string nm, int delay = 0);
|
||||
esp_err_t CaptureToBasisImage(CImageBasis *_Image, int delay = 0);
|
||||
int WaitBeforePicture;
|
||||
bool isImageSize;
|
||||
|
||||
bool CameraInitSuccessful;
|
||||
bool changedCameraSettings;
|
||||
bool DemoMode;
|
||||
bool SaveAllFiles;
|
||||
} camera_controll_config_temp_t;
|
||||
|
||||
extern camera_controll_config_temp_t CCstatus;
|
||||
|
||||
class CCamera
|
||||
{
|
||||
protected:
|
||||
void ledc_init(void);
|
||||
bool loadNextDemoImage(camera_fb_t *fb);
|
||||
long GetFileSize(std::string filename);
|
||||
void SetCamWindow(sensor_t *s, int frameSizeX, int frameSizeY, int xOffset, int yOffset, int xTotal, int yTotal, int xOutput, int yOutput, int imageVflip);
|
||||
void SetImageWidthHeightFromResolution(framesize_t resol);
|
||||
void SanitizeZoomParams(int imageSize, int frameSizeX, int frameSizeY, int &imageWidth, int &imageHeight, int &zoomOffsetX, int &zoomOffsetY);
|
||||
|
||||
public:
|
||||
CCamera(void);
|
||||
esp_err_t InitCam(void);
|
||||
|
||||
void LightOnOff(bool status);
|
||||
void LEDOnOff(bool status);
|
||||
|
||||
esp_err_t setSensorDatenFromCCstatus(void);
|
||||
esp_err_t getSensorDatenToCCstatus(void);
|
||||
|
||||
int ov5640_set_gainceiling(sensor_t *s, gainceiling_t level);
|
||||
|
||||
esp_err_t CaptureToHTTP(httpd_req_t *req, int delay = 0);
|
||||
esp_err_t CaptureToStream(httpd_req_t *req, bool FlashlightOn);
|
||||
|
||||
void SetQualityZoomSize(int qual, framesize_t resol, bool zoomEnabled, int zoomOffsetX, int zoomOffsetY, int imageSize, int imageVflip);
|
||||
void SetZoomSize(bool zoomEnabled, int zoomOffsetX, int zoomOffsetY, int imageSize, int imageVflip);
|
||||
void SetCamSharpness(bool _autoSharpnessEnabled, int _sharpnessLevel);
|
||||
|
||||
void SetLEDIntensity(float _intrel);
|
||||
bool testCamera(void);
|
||||
bool getCameraInitSuccessful(void);
|
||||
void useDemoMode(void);
|
||||
|
||||
framesize_t TextToFramesize(const char *text);
|
||||
|
||||
esp_err_t CaptureToFile(std::string nm, int delay = 0);
|
||||
esp_err_t CaptureToBasisImage(CImageBasis *_Image, int delay = 0);
|
||||
};
|
||||
|
||||
|
||||
extern CCamera Camera;
|
||||
|
||||
#endif
|
||||
@@ -3,71 +3,78 @@
|
||||
#include "ov2640_sharpness.h"
|
||||
|
||||
|
||||
#define OV2640_MAXLEVEL_SHARPNESS 6
|
||||
|
||||
const static uint8_t OV2640_SHARPNESS_AUTO[]=
|
||||
{
|
||||
0xFF, 0x00, 0xff,
|
||||
0x92, 0x01, 0xff,
|
||||
//reg, val, mask
|
||||
0xFF, 0x00, 0xFF,
|
||||
0x92, 0x01, 0xFF,
|
||||
0x93, 0x20, 0x20,
|
||||
0x00, 0x00, 0x00
|
||||
};
|
||||
|
||||
const static uint8_t OV2640_SHARPNESS_MANUAL[]=
|
||||
{
|
||||
0xFF, 0x00, 0xff,
|
||||
0x92, 0x01, 0xff,
|
||||
//reg, val, mask
|
||||
0xFF, 0x00, 0xFF,
|
||||
0x92, 0x01, 0xFF,
|
||||
0x93, 0x00, 0x20,
|
||||
0x00, 0x00, 0x00
|
||||
};
|
||||
|
||||
const static uint8_t OV2640_SHARPNESS_LEVEL0[]=
|
||||
{
|
||||
0xFF, 0x00, 0xff,
|
||||
0x92, 0x01, 0xff,
|
||||
0x93, 0xc0, 0x1f,
|
||||
//reg, val, mask
|
||||
0xFF, 0x00, 0xFF,
|
||||
0x92, 0x01, 0xFF,
|
||||
0x93, 0xC0, 0x1F,
|
||||
0x00, 0x00, 0x00
|
||||
};
|
||||
const static uint8_t OV2640_SHARPNESS_LEVEL1[]=
|
||||
{
|
||||
0xFF, 0x00, 0xff,
|
||||
0x92, 0x01, 0xff,
|
||||
0x93, 0xc1, 0x1f,
|
||||
//reg, val, mask
|
||||
0xFF, 0x00, 0xFF,
|
||||
0x92, 0x01, 0xFF,
|
||||
0x93, 0xC1, 0x1F,
|
||||
0x00, 0x00, 0x00
|
||||
};
|
||||
const static uint8_t OV2640_SHARPNESS_LEVEL2[]=
|
||||
{
|
||||
0xFF, 0x00, 0xff,
|
||||
0x92, 0x01, 0xff,
|
||||
0x93, 0xc2, 0x1f,
|
||||
//reg, val, mask
|
||||
0xFF, 0x00, 0xFF,
|
||||
0x92, 0x01, 0xFF,
|
||||
0x93, 0xC2, 0x1F,
|
||||
0x00, 0x00, 0x00
|
||||
};
|
||||
const static uint8_t OV2640_SHARPNESS_LEVEL3[]=
|
||||
{
|
||||
0xFF, 0x00, 0xff,
|
||||
0x92, 0x01, 0xff,
|
||||
0x93, 0xc4, 0x1f,
|
||||
//reg, val, mask
|
||||
0xFF, 0x00, 0xFF,
|
||||
0x92, 0x01, 0xFF,
|
||||
0x93, 0xC4, 0x1F,
|
||||
0x00, 0x00, 0x00
|
||||
};
|
||||
const static uint8_t OV2640_SHARPNESS_LEVEL4[]=
|
||||
{
|
||||
0xFF, 0x00, 0xff,
|
||||
0x92, 0x01, 0xff,
|
||||
0x93, 0xc8, 0x1f,
|
||||
//reg, val, mask
|
||||
0xFF, 0x00, 0xFF,
|
||||
0x92, 0x01, 0xFF,
|
||||
0x93, 0xC8, 0x1F,
|
||||
0x00, 0x00, 0x00
|
||||
};
|
||||
const static uint8_t OV2640_SHARPNESS_LEVEL5[]=
|
||||
{
|
||||
0xFF, 0x00, 0xff,
|
||||
0x92, 0x01, 0xff,
|
||||
0x93, 0xd0, 0x1f,
|
||||
//reg, val, mask
|
||||
0xFF, 0x00, 0xFF,
|
||||
0x92, 0x01, 0xFF,
|
||||
0x93, 0xD0, 0x1F,
|
||||
0x00, 0x00, 0x00
|
||||
};
|
||||
const static uint8_t OV2640_SHARPNESS_LEVEL6[]=
|
||||
{
|
||||
0xFF, 0x00, 0xff,
|
||||
0x92, 0x01, 0xff,
|
||||
0x93, 0xdf, 0x1f,
|
||||
//reg, val, mask
|
||||
0xFF, 0x00, 0xFF,
|
||||
0x92, 0x01, 0xFF,
|
||||
0x93, 0xDF, 0x1F,
|
||||
0x00, 0x00, 0x00
|
||||
};
|
||||
|
||||
@@ -82,6 +89,9 @@ const static uint8_t *OV2640_SETTING_SHARPNESS[]=
|
||||
OV2640_SHARPNESS_LEVEL6 // +3 sharpness
|
||||
};
|
||||
|
||||
#define OV2640_MAXLEVEL_SHARPNESS 6
|
||||
|
||||
|
||||
static int table_mask_write(sensor_t *sensor, const uint8_t* ptab)
|
||||
{
|
||||
uint8_t address;
|
||||
@@ -91,34 +101,52 @@ static int table_mask_write(sensor_t *sensor, const uint8_t* ptab)
|
||||
const uint8_t *pdata = ptab;
|
||||
|
||||
if (pdata == NULL)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
while (1)
|
||||
{
|
||||
address = *pdata++;
|
||||
value = *pdata++;
|
||||
mask = *pdata++;
|
||||
|
||||
if ((address == 0) && (value == 0) && (mask == 0))
|
||||
{
|
||||
break;
|
||||
}
|
||||
|
||||
sensor->set_reg(sensor, address, mask, value);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
int ov2640_enable_auto_sharpness(sensor_t *sensor)
|
||||
{
|
||||
table_mask_write(sensor, OV2640_SHARPNESS_AUTO);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
int ov2640_set_sharpness(sensor_t *sensor, int sharpness)
|
||||
{
|
||||
if ((sharpness < -3) || (sharpness > OV2640_MAXLEVEL_SHARPNESS - 3))
|
||||
return -1;
|
||||
int sharpness_temp = 0;
|
||||
|
||||
if (sharpness < -3)
|
||||
{
|
||||
sharpness_temp = -3;
|
||||
}
|
||||
|
||||
if (sharpness > OV2640_MAXLEVEL_SHARPNESS - 3)
|
||||
{
|
||||
sharpness_temp = OV2640_MAXLEVEL_SHARPNESS - 3;
|
||||
}
|
||||
|
||||
table_mask_write(sensor, OV2640_SHARPNESS_MANUAL);
|
||||
table_mask_write(sensor, OV2640_SETTING_SHARPNESS[sharpness + 3]);
|
||||
table_mask_write(sensor, OV2640_SETTING_SHARPNESS[sharpness_temp + 3]);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -5,6 +5,7 @@
|
||||
|
||||
#include "esp_camera.h"
|
||||
#include "ClassControllCamera.h"
|
||||
#include "MainFlowControl.h"
|
||||
|
||||
#include "ClassLogFile.h"
|
||||
#include "esp_log.h"
|
||||
@@ -13,191 +14,187 @@
|
||||
|
||||
static const char *TAG = "server_cam";
|
||||
|
||||
void PowerResetCamera()
|
||||
{
|
||||
#if CAM_PIN_PWDN == GPIO_NUM_NC // Use reset only if pin is available
|
||||
LogFile.WriteToFile(ESP_LOG_DEBUG, TAG, "No power down pin availbale to reset camera");
|
||||
#else
|
||||
ESP_LOGD(TAG, "Resetting camera by power down line");
|
||||
gpio_config_t conf;
|
||||
conf.intr_type = GPIO_INTR_DISABLE;
|
||||
conf.pin_bit_mask = 1LL << CAM_PIN_PWDN;
|
||||
conf.mode = GPIO_MODE_OUTPUT;
|
||||
conf.pull_down_en = GPIO_PULLDOWN_DISABLE;
|
||||
conf.pull_up_en = GPIO_PULLUP_DISABLE;
|
||||
gpio_config(&conf);
|
||||
|
||||
void PowerResetCamera(){
|
||||
|
||||
ESP_LOGD(TAG, "Resetting camera by power down line");
|
||||
gpio_config_t conf;
|
||||
conf.intr_type = GPIO_INTR_DISABLE;
|
||||
conf.pin_bit_mask = 1LL << GPIO_NUM_32;
|
||||
conf.mode = GPIO_MODE_OUTPUT;
|
||||
conf.pull_down_en = GPIO_PULLDOWN_DISABLE;
|
||||
conf.pull_up_en = GPIO_PULLUP_DISABLE;
|
||||
gpio_config(&conf);
|
||||
|
||||
// carefull, logic is inverted compared to reset pin
|
||||
gpio_set_level(GPIO_NUM_32, 1);
|
||||
vTaskDelay(1000 / portTICK_PERIOD_MS);
|
||||
gpio_set_level(GPIO_NUM_32, 0);
|
||||
vTaskDelay(1000 / portTICK_PERIOD_MS);
|
||||
// carefull, logic is inverted compared to reset pin
|
||||
gpio_set_level(CAM_PIN_PWDN, 1);
|
||||
vTaskDelay(1000 / portTICK_PERIOD_MS);
|
||||
gpio_set_level(CAM_PIN_PWDN, 0);
|
||||
vTaskDelay(1000 / portTICK_PERIOD_MS);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
esp_err_t handler_lightOn(httpd_req_t *req)
|
||||
{
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_lightOn - Start");
|
||||
ESP_LOGD(TAG, "handler_lightOn uri: %s", req->uri);
|
||||
#endif
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_lightOn - Start");
|
||||
ESP_LOGD(TAG, "handler_lightOn uri: %s", req->uri);
|
||||
#endif
|
||||
|
||||
if (Camera.getCameraInitSuccessful())
|
||||
if (Camera.getCameraInitSuccessful())
|
||||
{
|
||||
Camera.LightOnOff(true);
|
||||
const char* resp_str = (const char*) req->user_ctx;
|
||||
const char *resp_str = (const char *)req->user_ctx;
|
||||
httpd_resp_send(req, resp_str, strlen(resp_str));
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
httpd_resp_send_err(req, HTTPD_403_FORBIDDEN, "Camera not initialized: REST API /lighton not available!");
|
||||
return ESP_ERR_NOT_FOUND;
|
||||
}
|
||||
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_lightOn - Done");
|
||||
#endif
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_lightOn - Done");
|
||||
#endif
|
||||
|
||||
return ESP_OK;
|
||||
}
|
||||
|
||||
|
||||
esp_err_t handler_lightOff(httpd_req_t *req)
|
||||
{
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_lightOff - Start");
|
||||
ESP_LOGD(TAG, "handler_lightOff uri: %s", req->uri);
|
||||
#endif
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_lightOff - Start");
|
||||
ESP_LOGD(TAG, "handler_lightOff uri: %s", req->uri);
|
||||
#endif
|
||||
|
||||
if (Camera.getCameraInitSuccessful())
|
||||
if (Camera.getCameraInitSuccessful())
|
||||
{
|
||||
Camera.LightOnOff(false);
|
||||
const char* resp_str = (const char*) req->user_ctx;
|
||||
httpd_resp_send(req, resp_str, strlen(resp_str));
|
||||
const char *resp_str = (const char *)req->user_ctx;
|
||||
httpd_resp_send(req, resp_str, strlen(resp_str));
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
httpd_resp_send_err(req, HTTPD_403_FORBIDDEN, "Camera not initialized: REST API /lightoff not available!");
|
||||
return ESP_ERR_NOT_FOUND;
|
||||
}
|
||||
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_lightOff - Done");
|
||||
#endif
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_lightOff - Done");
|
||||
#endif
|
||||
|
||||
return ESP_OK;
|
||||
}
|
||||
|
||||
|
||||
esp_err_t handler_capture(httpd_req_t *req)
|
||||
{
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_capture - Start");
|
||||
#endif
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_capture - Start");
|
||||
#endif
|
||||
|
||||
if (Camera.getCameraInitSuccessful())
|
||||
if (Camera.getCameraInitSuccessful())
|
||||
{
|
||||
int quality;
|
||||
framesize_t res;
|
||||
bool zoomEnabled;
|
||||
int zoomMode;
|
||||
int zoomOffsetX;
|
||||
int zoomOffsetY;
|
||||
// If the camera settings were changed by creating a new reference image, they must be reset
|
||||
if (CFstatus.changedCameraSettings)
|
||||
{
|
||||
Camera.setSensorDatenFromCCstatus(); // CCstatus >>> Kamera
|
||||
Camera.SetQualityZoomSize(CCstatus.ImageQuality, CCstatus.ImageFrameSize, CCstatus.ImageZoomEnabled, CCstatus.ImageZoomOffsetX, CCstatus.ImageZoomOffsetY, CCstatus.ImageZoomSize, CCstatus.ImageVflip);
|
||||
CFstatus.changedCameraSettings = false;
|
||||
}
|
||||
|
||||
Camera.GetCameraParameter(req, quality, res, zoomEnabled, zoomMode, zoomOffsetX, zoomOffsetY);
|
||||
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
ESP_LOGD(TAG, "Size: %d, Quality: %d", res, quality);
|
||||
#endif
|
||||
|
||||
Camera.SetQualitySize(quality, res, zoomEnabled, zoomMode, zoomOffsetX, zoomOffsetY);
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
ESP_LOGD(TAG, "Size: %d, Quality: %d", CCstatus.ImageFrameSize, CCstatus.ImageQuality);
|
||||
#endif
|
||||
|
||||
esp_err_t result;
|
||||
result = Camera.CaptureToHTTP(req);
|
||||
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_capture - Done");
|
||||
#endif
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_capture - Done");
|
||||
#endif
|
||||
|
||||
return result;
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
httpd_resp_send_err(req, HTTPD_403_FORBIDDEN, "Camera not initialized: REST API /capture not available!");
|
||||
return ESP_ERR_NOT_FOUND;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
esp_err_t handler_capture_with_light(httpd_req_t *req)
|
||||
{
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_capture_with_light - Start");
|
||||
#endif
|
||||
|
||||
if (Camera.getCameraInitSuccessful())
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_capture_with_light - Start");
|
||||
#endif
|
||||
|
||||
if (Camera.getCameraInitSuccessful())
|
||||
{
|
||||
char _query[100];
|
||||
char _delay[10];
|
||||
|
||||
int quality;
|
||||
framesize_t res;
|
||||
bool zoomEnabled;
|
||||
int zoomMode;
|
||||
int zoomOffsetX;
|
||||
int zoomOffsetY;
|
||||
int delay = 2500;
|
||||
|
||||
if (httpd_req_get_url_query_str(req, _query, 100) == ESP_OK)
|
||||
{
|
||||
ESP_LOGD(TAG, "Query: %s", _query);
|
||||
|
||||
if (httpd_query_key_value(_query, "delay", _delay, 10) == ESP_OK)
|
||||
{
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
ESP_LOGD(TAG, "Delay: %s", _delay);
|
||||
#endif
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
ESP_LOGD(TAG, "Delay: %s", _delay);
|
||||
#endif
|
||||
delay = atoi(_delay);
|
||||
|
||||
if (delay < 0)
|
||||
{
|
||||
delay = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
Camera.GetCameraParameter(req, quality, res, zoomEnabled, zoomMode, zoomOffsetX, zoomOffsetY);
|
||||
// If the camera settings were changed by creating a new reference image, they must be reset
|
||||
if (CFstatus.changedCameraSettings)
|
||||
{
|
||||
Camera.setSensorDatenFromCCstatus(); // CCstatus >>> Kamera
|
||||
Camera.SetQualityZoomSize(CCstatus.ImageQuality, CCstatus.ImageFrameSize, CCstatus.ImageZoomEnabled, CCstatus.ImageZoomOffsetX, CCstatus.ImageZoomOffsetY, CCstatus.ImageZoomSize, CCstatus.ImageVflip);
|
||||
CFstatus.changedCameraSettings = false;
|
||||
}
|
||||
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
ESP_LOGD(TAG, "Size: %d, Quality: %d", res, quality);
|
||||
#endif
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
ESP_LOGD(TAG, "Size: %d, Quality: %d", CCstatus.ImageFrameSize, CCstatus.ImageQuality);
|
||||
#endif
|
||||
|
||||
Camera.SetQualitySize(quality, res, zoomEnabled, zoomMode, zoomOffsetX, zoomOffsetY);
|
||||
Camera.LightOnOff(true);
|
||||
const TickType_t xDelay = delay / portTICK_PERIOD_MS;
|
||||
vTaskDelay( xDelay );
|
||||
vTaskDelay(xDelay);
|
||||
|
||||
esp_err_t result;
|
||||
result = Camera.CaptureToHTTP(req);
|
||||
result = Camera.CaptureToHTTP(req);
|
||||
|
||||
Camera.LightOnOff(false);
|
||||
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_capture_with_light - Done");
|
||||
#endif
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_capture_with_light - Done");
|
||||
#endif
|
||||
|
||||
return result;
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
httpd_resp_send_err(req, HTTPD_403_FORBIDDEN, "Camera not initialized: REST API /capture_with_flashlight not available!");
|
||||
return ESP_ERR_NOT_FOUND;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
esp_err_t handler_capture_save_to_file(httpd_req_t *req)
|
||||
{
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_capture_save_to_file - Start");
|
||||
#endif
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_capture_save_to_file - Start");
|
||||
#endif
|
||||
|
||||
if (Camera.getCameraInitSuccessful())
|
||||
if (Camera.getCameraInitSuccessful())
|
||||
{
|
||||
char _query[100];
|
||||
char _delay[10];
|
||||
@@ -205,98 +202,102 @@ esp_err_t handler_capture_save_to_file(httpd_req_t *req)
|
||||
char filename[100];
|
||||
std::string fn = "/sdcard/";
|
||||
|
||||
|
||||
int quality;
|
||||
framesize_t res;
|
||||
bool zoomEnabled;
|
||||
int zoomMode;
|
||||
int zoomOffsetX;
|
||||
int zoomOffsetY;
|
||||
|
||||
if (httpd_req_get_url_query_str(req, _query, 100) == ESP_OK)
|
||||
{
|
||||
ESP_LOGD(TAG, "Query: %s", _query);
|
||||
|
||||
if (httpd_query_key_value(_query, "filename", filename, 100) == ESP_OK)
|
||||
{
|
||||
fn.append(filename);
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
ESP_LOGD(TAG, "Filename: %s", fn.c_str());
|
||||
#endif
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
ESP_LOGD(TAG, "Filename: %s", fn.c_str());
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
fn.append("noname.jpg");
|
||||
}
|
||||
|
||||
if (httpd_query_key_value(_query, "delay", _delay, 10) == ESP_OK)
|
||||
{
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
ESP_LOGD(TAG, "Delay: %s", _delay);
|
||||
#endif
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
ESP_LOGD(TAG, "Delay: %s", _delay);
|
||||
#endif
|
||||
delay = atoi(_delay);
|
||||
|
||||
if (delay < 0)
|
||||
{
|
||||
delay = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
fn.append("noname.jpg");
|
||||
}
|
||||
|
||||
Camera.GetCameraParameter(req, quality, res, zoomEnabled, zoomMode, zoomOffsetX, zoomOffsetY);
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
ESP_LOGD(TAG, "Size: %d, Quality: %d", res, quality);
|
||||
#endif
|
||||
Camera.SetQualitySize(quality, res, zoomEnabled, zoomMode, zoomOffsetX, zoomOffsetY);
|
||||
// If the camera settings were changed by creating a new reference image, they must be reset
|
||||
if (CFstatus.changedCameraSettings)
|
||||
{
|
||||
Camera.setSensorDatenFromCCstatus(); // CCstatus >>> Kamera
|
||||
Camera.SetQualityZoomSize(CCstatus.ImageQuality, CCstatus.ImageFrameSize, CCstatus.ImageZoomEnabled, CCstatus.ImageZoomOffsetX, CCstatus.ImageZoomOffsetY, CCstatus.ImageZoomSize, CCstatus.ImageVflip);
|
||||
CFstatus.changedCameraSettings = false;
|
||||
}
|
||||
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
ESP_LOGD(TAG, "Size: %d, Quality: %d", CCstatus.ImageFrameSize, CCstatus.ImageQuality);
|
||||
#endif
|
||||
|
||||
esp_err_t result;
|
||||
result = Camera.CaptureToFile(fn, delay);
|
||||
result = Camera.CaptureToFile(fn, delay);
|
||||
|
||||
const char* resp_str = (const char*) fn.c_str();
|
||||
const char *resp_str = (const char *)fn.c_str();
|
||||
httpd_resp_send(req, resp_str, strlen(resp_str));
|
||||
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_capture_save_to_file - Done");
|
||||
#endif
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
LogFile.WriteHeapInfo("handler_capture_save_to_file - Done");
|
||||
#endif
|
||||
|
||||
return result;
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
httpd_resp_send_err(req, HTTPD_403_FORBIDDEN, "Camera not initialized: REST API /save not available!");
|
||||
return ESP_ERR_NOT_FOUND;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void register_server_camera_uri(httpd_handle_t server)
|
||||
{
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
#ifdef DEBUG_DETAIL_ON
|
||||
ESP_LOGI(TAG, "server_part_camera - Registering URI handlers");
|
||||
#endif
|
||||
|
||||
httpd_uri_t camuri = { };
|
||||
camuri.method = HTTP_GET;
|
||||
httpd_uri_t camuri = {};
|
||||
camuri.method = HTTP_GET;
|
||||
|
||||
camuri.uri = "/lighton";
|
||||
camuri.handler = handler_lightOn;
|
||||
camuri.user_ctx = (void*) "Light On";
|
||||
camuri.uri = "/lighton";
|
||||
camuri.handler = handler_lightOn;
|
||||
camuri.user_ctx = (void *)"Light On";
|
||||
httpd_register_uri_handler(server, &camuri);
|
||||
|
||||
camuri.uri = "/lightoff";
|
||||
camuri.handler = handler_lightOff;
|
||||
camuri.user_ctx = (void*) "Light Off";
|
||||
httpd_register_uri_handler(server, &camuri);
|
||||
camuri.uri = "/lightoff";
|
||||
camuri.handler = handler_lightOff;
|
||||
camuri.user_ctx = (void *)"Light Off";
|
||||
httpd_register_uri_handler(server, &camuri);
|
||||
|
||||
camuri.uri = "/capture";
|
||||
camuri.handler = handler_capture;
|
||||
camuri.user_ctx = NULL;
|
||||
httpd_register_uri_handler(server, &camuri);
|
||||
camuri.uri = "/capture";
|
||||
camuri.handler = handler_capture;
|
||||
camuri.user_ctx = NULL;
|
||||
httpd_register_uri_handler(server, &camuri);
|
||||
|
||||
camuri.uri = "/capture_with_flashlight";
|
||||
camuri.handler = handler_capture_with_light;
|
||||
camuri.user_ctx = NULL;
|
||||
httpd_register_uri_handler(server, &camuri);
|
||||
camuri.uri = "/capture_with_flashlight";
|
||||
camuri.handler = handler_capture_with_light;
|
||||
camuri.user_ctx = NULL;
|
||||
httpd_register_uri_handler(server, &camuri);
|
||||
|
||||
camuri.uri = "/save";
|
||||
camuri.handler = handler_capture_save_to_file;
|
||||
camuri.user_ctx = NULL;
|
||||
httpd_register_uri_handler(server, &camuri);
|
||||
camuri.uri = "/save";
|
||||
camuri.handler = handler_capture_save_to_file;
|
||||
camuri.user_ctx = NULL;
|
||||
httpd_register_uri_handler(server, &camuri);
|
||||
}
|
||||
|
||||
@@ -10,7 +10,6 @@
|
||||
//#include "ClassControllCamera.h"
|
||||
|
||||
void register_server_camera_uri(httpd_handle_t server);
|
||||
|
||||
void PowerResetCamera();
|
||||
|
||||
#endif
|
||||
Reference in New Issue
Block a user