Initial Code v0.1.0

This commit is contained in:
jomjol
2020-08-07 17:42:29 +02:00
parent 0e2475bf0d
commit 4fe26dc0d8
269 changed files with 87264 additions and 0 deletions

View File

@@ -0,0 +1,254 @@
#include "ClassControllCamera.h"
#include <stdio.h>
#include "driver/gpio.h"
#include "esp_timer.h"
#include "esp_log.h"
#include "Helper.h"
#include "CFindTemplate.h"
#include "camera_define.h"
CCamera Camera;
#define FLASH_GPIO GPIO_NUM_4
typedef struct {
httpd_req_t *req;
size_t len;
} jpg_chunking_t;
static size_t jpg_encode_stream(void * arg, size_t index, const void* data, size_t len){
jpg_chunking_t *j = (jpg_chunking_t *)arg;
if(!index){
j->len = 0;
}
if(httpd_resp_send_chunk(j->req, (const char *)data, len) != ESP_OK){
return 0;
}
j->len += len;
return len;
}
void CCamera::SetQualitySize(int qual, framesize_t resol)
{
sensor_t * s = esp_camera_sensor_get();
s->set_quality(s, qual);
s->set_framesize(s, resol);
ActualResolution = resol;
ActualQuality = qual;
}
esp_err_t CCamera::CaptureToFile(std::string nm, int delay)
{
// nm = "/sdcard/josef_zw.bmp";
string ftype;
if (delay > 0)
{
LightOnOff(true);
const TickType_t xDelay = delay / portTICK_PERIOD_MS;
vTaskDelay( xDelay );
}
camera_fb_t * fb = esp_camera_fb_get();
if (!fb) {
ESP_LOGE(TAGCAMERACLASS, "Camera Capture Failed");
return ESP_FAIL;
}
printf("w %d, h %d, size %d\n", fb->width, fb->height, fb->len);
nm = FormatFileName(nm);
printf("Save Camera to : %s\n", nm.c_str());
ftype = toUpper(getFileType(nm));
printf("Filetype: %s\n", ftype.c_str());
uint8_t * buf = NULL;
size_t buf_len = 0;
bool converted = false;
if (ftype.compare("BMP") == 0)
{
frame2bmp(fb, &buf, &buf_len);
converted = true;
}
if (ftype.compare("JPG") == 0)
{
if(fb->format != PIXFORMAT_JPEG){
bool jpeg_converted = frame2jpg(fb, ActualQuality, &buf, &buf_len);
converted = true;
if(!jpeg_converted){
ESP_LOGE(TAGCAMERACLASS, "JPEG compression failed");
}
} else {
buf_len = fb->len;
buf = fb->buf;
}
}
FILE * fp = fopen(nm.c_str(), "wb");
if (fp == NULL) /* If an error occurs during the file creation */
{
fprintf(stderr, "fopen() failed for '%s'\n", nm.c_str());
}
else
{
fwrite(buf, sizeof(uint8_t), buf_len, fp);
fclose(fp);
}
if (converted)
free(buf);
esp_camera_fb_return(fb);
if (delay > 0)
{
LightOnOff(false);
}
return ESP_OK;
}
esp_err_t CCamera::CaptureToHTTP(httpd_req_t *req, int delay)
{
camera_fb_t * fb = NULL;
esp_err_t res = ESP_OK;
size_t fb_len = 0;
int64_t fr_start = esp_timer_get_time();
fb = esp_camera_fb_get();
if (!fb) {
ESP_LOGE(TAGCAMERACLASS, "Camera capture failed");
httpd_resp_send_500(req);
return ESP_FAIL;
}
res = httpd_resp_set_type(req, "image/jpeg");
if(res == ESP_OK){
res = httpd_resp_set_hdr(req, "Content-Disposition", "inline; filename=capture.jpg");
}
if(res == ESP_OK){
if(fb->format == PIXFORMAT_JPEG){
fb_len = fb->len;
res = httpd_resp_send(req, (const char *)fb->buf, fb->len);
} else {
jpg_chunking_t jchunk = {req, 0};
res = frame2jpg_cb(fb, 80, jpg_encode_stream, &jchunk)?ESP_OK:ESP_FAIL;
httpd_resp_send_chunk(req, NULL, 0);
fb_len = jchunk.len;
}
}
esp_camera_fb_return(fb);
int64_t fr_end = esp_timer_get_time();
ESP_LOGI(TAGCAMERACLASS, "JPG: %uKB %ums", (uint32_t)(fb_len/1024), (uint32_t)((fr_end - fr_start)/1000));
return res;
}
void CCamera::LightOnOff(bool status)
{
// Init the GPIO
gpio_pad_select_gpio(FLASH_GPIO);
/* Set the GPIO as a push/pull output */
gpio_set_direction(FLASH_GPIO, GPIO_MODE_OUTPUT);
if (status)
gpio_set_level(FLASH_GPIO, 1);
else
gpio_set_level(FLASH_GPIO, 0);
}
void CCamera::GetCameraParameter(httpd_req_t *req, int &qual, framesize_t &resol)
{
char _query[100];
char _qual[10];
char _size[10];
resol = ActualResolution;
qual = ActualQuality;
if (httpd_req_get_url_query_str(req, _query, 100) == ESP_OK)
{
printf("Query: "); printf(_query); printf("\n");
if (httpd_query_key_value(_query, "size", _size, 10) == ESP_OK)
{
printf("Size: "); printf(_size); printf("\n");
if (strcmp(_size, "QVGA") == 0)
resol = FRAMESIZE_QVGA; // 320x240
if (strcmp(_size, "VGA") == 0)
resol = FRAMESIZE_VGA; // 640x480
if (strcmp(_size, "SVGA") == 0)
resol = FRAMESIZE_SVGA; // 800x600
if (strcmp(_size, "XGA") == 0)
resol = FRAMESIZE_XGA; // 1024x768
if (strcmp(_size, "SXGA") == 0)
resol = FRAMESIZE_SXGA; // 1280x1024
if (strcmp(_size, "UXGA") == 0)
resol = FRAMESIZE_UXGA; // 1600x1200
}
if (httpd_query_key_value(_query, "quality", _qual, 10) == ESP_OK)
{
printf("Quality: "); printf(_qual); printf("\n");
qual = atoi(_qual);
if (qual > 63)
qual = 63;
if (qual < 0)
qual = 0;
}
};
}
framesize_t CCamera::TextToFramesize(const char * _size)
{
if (strcmp(_size, "QVGA") == 0)
return FRAMESIZE_QVGA; // 320x240
if (strcmp(_size, "VGA") == 0)
return FRAMESIZE_VGA; // 640x480
if (strcmp(_size, "SVGA") == 0)
return FRAMESIZE_SVGA; // 800x600
if (strcmp(_size, "XGA") == 0)
return FRAMESIZE_XGA; // 1024x768
if (strcmp(_size, "SXGA") == 0)
return FRAMESIZE_SXGA; // 1280x1024
if (strcmp(_size, "UXGA") == 0)
return FRAMESIZE_UXGA; // 1600x1200
return ActualResolution;
}
CCamera::CCamera()
{
printf("CreateClassCamera\n");
}
esp_err_t CCamera::InitCam()
{
printf("Init Flash\n");
//power up the camera if PWDN pin is defined
if(PWDN_GPIO_NUM != -1){
// Init the GPIO
gpio_pad_select_gpio(PWDN_GPIO_NUM);
/* Set the GPIO as a push/pull output */
gpio_set_direction(PWDN_GPIO_NUM, GPIO_MODE_OUTPUT);
gpio_set_level(PWDN_GPIO_NUM, 0);
}
printf("Init Camera\n");
ActualQuality = camera_config.jpeg_quality;
ActualResolution = camera_config.frame_size;
//initialize the camera
esp_err_t err = esp_camera_init(&camera_config);
if (err != ESP_OK) {
ESP_LOGE(TAGCAMERACLASS, "Camera Init Failed");
return err;
}
return ESP_OK;
}

View File

@@ -0,0 +1,46 @@
#ifndef CLASSCONTROLLCAMERA_H
#define CLASSCONTROLLCAMERA_H
#include <string>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/queue.h"
#include "freertos/event_groups.h"
#include "esp_camera.h"
#include <string>
#include "esp_http_server.h"
#define CAMERA_MODEL_AI_THINKER
static const char *TAGCAMERACLASS = "server_part_camera";
class CCamera {
protected:
int ActualQuality;
framesize_t ActualResolution;
public:
CCamera();
esp_err_t InitCam();
void LightOnOff(bool status);
esp_err_t CaptureToHTTP(httpd_req_t *req, int delay = 0);
void SetQualitySize(int qual, framesize_t resol);
void GetCameraParameter(httpd_req_t *req, int &qual, framesize_t &resol);
framesize_t TextToFramesize(const char * text);
esp_err_t CaptureToFile(std::string nm, int delay = 0);
};
extern CCamera Camera;
#endif

View File

@@ -0,0 +1,97 @@
#define CAMERA_MODEL_AI_THINKER
#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_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_AI_THINKER)
#define PWDN_GPIO_NUM GPIO_NUM_32
#define RESET_GPIO_NUM -1
#define XCLK_GPIO_NUM GPIO_NUM_0
#define SIOD_GPIO_NUM GPIO_NUM_26
#define SIOC_GPIO_NUM GPIO_NUM_27
#define Y9_GPIO_NUM GPIO_NUM_35
#define Y8_GPIO_NUM GPIO_NUM_34
#define Y7_GPIO_NUM GPIO_NUM_39
#define Y6_GPIO_NUM GPIO_NUM_36
#define Y5_GPIO_NUM GPIO_NUM_21
#define Y4_GPIO_NUM GPIO_NUM_19
#define Y3_GPIO_NUM GPIO_NUM_18
#define Y2_GPIO_NUM GPIO_NUM_5
#define VSYNC_GPIO_NUM GPIO_NUM_25
#define HREF_GPIO_NUM GPIO_NUM_23
#define PCLK_GPIO_NUM GPIO_NUM_22
#else
#error "Camera model not selected"
#endif
static camera_config_t camera_config = {
.pin_pwdn = PWDN_GPIO_NUM,
.pin_reset = RESET_GPIO_NUM,
.pin_xclk = XCLK_GPIO_NUM,
.pin_sscb_sda = SIOD_GPIO_NUM,
.pin_sscb_scl = SIOC_GPIO_NUM,
.pin_d7 = Y9_GPIO_NUM,
.pin_d6 = Y8_GPIO_NUM,
.pin_d5 = Y7_GPIO_NUM,
.pin_d4 = Y6_GPIO_NUM,
.pin_d3 = Y5_GPIO_NUM,
.pin_d2 = Y4_GPIO_NUM,
.pin_d1 = Y3_GPIO_NUM,
.pin_d0 = Y2_GPIO_NUM,
.pin_vsync = VSYNC_GPIO_NUM,
.pin_href = HREF_GPIO_NUM,
.pin_pclk = PCLK_GPIO_NUM,
//XCLK 20MHz or 10MHz for OV2640 double FPS (Experimental)
.xclk_freq_hz = 20000000,
.ledc_timer = LEDC_TIMER_0,
.ledc_channel = LEDC_CHANNEL_0,
.pixel_format = PIXFORMAT_JPEG,//YUV422,GRAYSCALE,RGB565,JPEG
// .pixel_format = PIXFORMAT_RGB888,//YUV422,GRAYSCALE,RGB565,JPEG
.frame_size = FRAMESIZE_UXGA,//QQVGA-QXGA Do not use sizes above QVGA when not JPEG
.jpeg_quality = 5, //0-63 lower number means higher quality
.fb_count = 1 //if more than one, i2s runs in continuous mode. Use only with JPEG
};

View File

@@ -0,0 +1,200 @@
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*
* Example Use
*
static camera_config_t camera_example_config = {
.pin_pwdn = PIN_PWDN,
.pin_reset = PIN_RESET,
.pin_xclk = PIN_XCLK,
.pin_sscb_sda = PIN_SIOD,
.pin_sscb_scl = PIN_SIOC,
.pin_d7 = PIN_D7,
.pin_d6 = PIN_D6,
.pin_d5 = PIN_D5,
.pin_d4 = PIN_D4,
.pin_d3 = PIN_D3,
.pin_d2 = PIN_D2,
.pin_d1 = PIN_D1,
.pin_d0 = PIN_D0,
.pin_vsync = PIN_VSYNC,
.pin_href = PIN_HREF,
.pin_pclk = PIN_PCLK,
.xclk_freq_hz = 20000000,
.ledc_timer = LEDC_TIMER_0,
.ledc_channel = LEDC_CHANNEL_0,
.pixel_format = PIXFORMAT_JPEG,
.frame_size = FRAMESIZE_SVGA,
.jpeg_quality = 10,
.fb_count = 2
};
esp_err_t camera_example_init(){
return esp_camera_init(&camera_example_config);
}
esp_err_t camera_example_capture(){
//capture a frame
camera_fb_t * fb = esp_camera_fb_get();
if (!fb) {
ESP_LOGE(TAG, "Frame buffer could not be acquired");
return ESP_FAIL;
}
//replace this with your own function
display_image(fb->width, fb->height, fb->pixformat, fb->buf, fb->len);
//return the frame buffer back to be reused
esp_camera_fb_return(fb);
return ESP_OK;
}
*/
#pragma once
#ifndef ESPCAMERADEF
#define ESPCAMERADEF
#include "esp_err.h"
#include "driver/ledc.h"
#include "sensor.h"
#include "sys/time.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Configuration structure for camera initialization
*/
typedef struct {
int pin_pwdn; /*!< GPIO pin for camera power down line */
int pin_reset; /*!< GPIO pin for camera reset line */
int pin_xclk; /*!< GPIO pin for camera XCLK line */
int pin_sscb_sda; /*!< GPIO pin for camera SDA line */
int pin_sscb_scl; /*!< GPIO pin for camera SCL line */
int pin_d7; /*!< GPIO pin for camera D7 line */
int pin_d6; /*!< GPIO pin for camera D6 line */
int pin_d5; /*!< GPIO pin for camera D5 line */
int pin_d4; /*!< GPIO pin for camera D4 line */
int pin_d3; /*!< GPIO pin for camera D3 line */
int pin_d2; /*!< GPIO pin for camera D2 line */
int pin_d1; /*!< GPIO pin for camera D1 line */
int pin_d0; /*!< GPIO pin for camera D0 line */
int pin_vsync; /*!< GPIO pin for camera VSYNC line */
int pin_href; /*!< GPIO pin for camera HREF line */
int pin_pclk; /*!< GPIO pin for camera PCLK line */
int xclk_freq_hz; /*!< Frequency of XCLK signal, in Hz. Either 20KHz or 10KHz for OV2640 double FPS (Experimental) */
ledc_timer_t ledc_timer; /*!< LEDC timer to be used for generating XCLK */
ledc_channel_t ledc_channel; /*!< LEDC channel to be used for generating XCLK */
pixformat_t pixel_format; /*!< Format of the pixel data: PIXFORMAT_ + YUV422|GRAYSCALE|RGB565|JPEG */
framesize_t frame_size; /*!< Size of the output image: FRAMESIZE_ + QVGA|CIF|VGA|SVGA|XGA|SXGA|UXGA */
int jpeg_quality; /*!< Quality of JPEG output. 0-63 lower means higher quality */
size_t fb_count; /*!< Number of frame buffers to be allocated. If more than one, then each frame will be acquired (double speed) */
} camera_config_t;
/**
* @brief Data structure of camera frame buffer
*/
typedef struct {
uint8_t * buf; /*!< Pointer to the pixel data */
size_t len; /*!< Length of the buffer in bytes */
size_t width; /*!< Width of the buffer in pixels */
size_t height; /*!< Height of the buffer in pixels */
pixformat_t format; /*!< Format of the pixel data */
struct timeval timestamp; /*!< Timestamp since boot of the first DMA buffer of the frame */
} camera_fb_t;
#define ESP_ERR_CAMERA_BASE 0x20000
#define ESP_ERR_CAMERA_NOT_DETECTED (ESP_ERR_CAMERA_BASE + 1)
#define ESP_ERR_CAMERA_FAILED_TO_SET_FRAME_SIZE (ESP_ERR_CAMERA_BASE + 2)
#define ESP_ERR_CAMERA_FAILED_TO_SET_OUT_FORMAT (ESP_ERR_CAMERA_BASE + 3)
#define ESP_ERR_CAMERA_NOT_SUPPORTED (ESP_ERR_CAMERA_BASE + 4)
/**
* @brief Initialize the camera driver
*
* @note call camera_probe before calling this function
*
* This function detects and configures camera over I2C interface,
* allocates framebuffer and DMA buffers,
* initializes parallel I2S input, and sets up DMA descriptors.
*
* Currently this function can only be called once and there is
* no way to de-initialize this module.
*
* @param config Camera configuration parameters
*
* @return ESP_OK on success
*/
esp_err_t esp_camera_init(const camera_config_t* config);
/**
* @brief Deinitialize the camera driver
*
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_STATE if the driver hasn't been initialized yet
*/
esp_err_t esp_camera_deinit();
/**
* @brief Obtain pointer to a frame buffer.
*
* @return pointer to the frame buffer
*/
camera_fb_t* esp_camera_fb_get();
/**
* @brief Return the frame buffer to be reused again.
*
* @param fb Pointer to the frame buffer
*/
void esp_camera_fb_return(camera_fb_t * fb);
/**
* @brief Get a pointer to the image sensor control structure
*
* @return pointer to the sensor
*/
sensor_t * esp_camera_sensor_get();
/**
* @brief Save camera settings to non-volatile-storage (NVS)
*
* @param key A unique nvs key name for the camera settings
*/
esp_err_t esp_camera_save_to_nvs(const char *key);
/**
* @brief Load camera settings from non-volatile-storage (NVS)
*
* @param key A unique nvs key name for the camera settings
*/
esp_err_t esp_camera_load_from_nvs(const char *key);
#ifdef __cplusplus
}
#endif
#include "img_converters.h"
#endif

View File

@@ -0,0 +1,126 @@
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef _IMG_CONVERTERS_H_
#define _IMG_CONVERTERS_H_
#ifdef __cplusplus
extern "C" {
#endif
#include <stddef.h>
#include <stdint.h>
#include <stdbool.h>
#include "esp_camera.h"
typedef size_t (* jpg_out_cb)(void * arg, size_t index, const void* data, size_t len);
/**
* @brief Convert image buffer to JPEG
*
* @param src Source buffer in RGB565, RGB888, YUYV or GRAYSCALE format
* @param src_len Length in bytes of the source buffer
* @param width Width in pixels of the source image
* @param height Height in pixels of the source image
* @param format Format of the source image
* @param quality JPEG quality of the resulting image
* @param cp Callback to be called to write the bytes of the output JPEG
* @param arg Pointer to be passed to the callback
*
* @return true on success
*/
bool fmt2jpg_cb(uint8_t *src, size_t src_len, uint16_t width, uint16_t height, pixformat_t format, uint8_t quality, jpg_out_cb cb, void * arg);
/**
* @brief Convert camera frame buffer to JPEG
*
* @param fb Source camera frame buffer
* @param quality JPEG quality of the resulting image
* @param cp Callback to be called to write the bytes of the output JPEG
* @param arg Pointer to be passed to the callback
*
* @return true on success
*/
bool frame2jpg_cb(camera_fb_t * fb, uint8_t quality, jpg_out_cb cb, void * arg);
/**
* @brief Convert image buffer to JPEG buffer
*
* @param src Source buffer in RGB565, RGB888, YUYV or GRAYSCALE format
* @param src_len Length in bytes of the source buffer
* @param width Width in pixels of the source image
* @param height Height in pixels of the source image
* @param format Format of the source image
* @param quality JPEG quality of the resulting image
* @param out Pointer to be populated with the address of the resulting buffer
* @param out_len Pointer to be populated with the length of the output buffer
*
* @return true on success
*/
bool fmt2jpg(uint8_t *src, size_t src_len, uint16_t width, uint16_t height, pixformat_t format, uint8_t quality, uint8_t ** out, size_t * out_len);
/**
* @brief Convert camera frame buffer to JPEG buffer
*
* @param fb Source camera frame buffer
* @param quality JPEG quality of the resulting image
* @param out Pointer to be populated with the address of the resulting buffer
* @param out_len Pointer to be populated with the length of the output buffer
*
* @return true on success
*/
bool frame2jpg(camera_fb_t * fb, uint8_t quality, uint8_t ** out, size_t * out_len);
/**
* @brief Convert image buffer to BMP buffer
*
* @param src Source buffer in JPEG, RGB565, RGB888, YUYV or GRAYSCALE format
* @param src_len Length in bytes of the source buffer
* @param width Width in pixels of the source image
* @param height Height in pixels of the source image
* @param format Format of the source image
* @param out Pointer to be populated with the address of the resulting buffer
* @param out_len Pointer to be populated with the length of the output buffer
*
* @return true on success
*/
bool fmt2bmp(uint8_t *src, size_t src_len, uint16_t width, uint16_t height, pixformat_t format, uint8_t ** out, size_t * out_len);
/**
* @brief Convert camera frame buffer to BMP buffer
*
* @param fb Source camera frame buffer
* @param out Pointer to be populated with the address of the resulting buffer
* @param out_len Pointer to be populated with the length of the output buffer
*
* @return true on success
*/
bool frame2bmp(camera_fb_t * fb, uint8_t ** out, size_t * out_len);
/**
* @brief Convert image buffer to RGB888 buffer (used for face detection)
*
* @param src Source buffer in JPEG, RGB565, RGB888, YUYV or GRAYSCALE format
* @param src_len Length in bytes of the source buffer
* @param format Format of the source image
* @param rgb_buf Pointer to the output buffer (width * height * 3)
*
* @return true on success
*/
bool fmt2rgb888(const uint8_t *src_buf, size_t src_len, pixformat_t format, uint8_t * rgb_buf);
#ifdef __cplusplus
}
#endif
#endif /* _IMG_CONVERTERS_H_ */

View File

@@ -0,0 +1,191 @@
/*
* This file is part of the OpenMV project.
* Copyright (c) 2013/2014 Ibrahim Abdelkader <i.abdalkader@gmail.com>
* This work is licensed under the MIT license, see the file LICENSE for details.
*
* Sensor abstraction layer.
*
*/
#ifndef __SENSOR_H__
#define __SENSOR_H__
#include <stdint.h>
#include <stdbool.h>
#define OV9650_PID (0x96)
#define OV7725_PID (0x77)
#define OV2640_PID (0x26)
#define OV3660_PID (0x36)
#define OV5640_PID (0x56)
typedef enum {
PIXFORMAT_RGB565, // 2BPP/RGB565
PIXFORMAT_YUV422, // 2BPP/YUV422
PIXFORMAT_GRAYSCALE, // 1BPP/GRAYSCALE
PIXFORMAT_JPEG, // JPEG/COMPRESSED
PIXFORMAT_RGB888, // 3BPP/RGB888
PIXFORMAT_RAW, // RAW
PIXFORMAT_RGB444, // 3BP2P/RGB444
PIXFORMAT_RGB555, // 3BP2P/RGB555
} pixformat_t;
typedef enum {
FRAMESIZE_96X96, // 96x96
FRAMESIZE_QQVGA, // 160x120
FRAMESIZE_QCIF, // 176x144
FRAMESIZE_HQVGA, // 240x176
FRAMESIZE_240X240, // 240x240
FRAMESIZE_QVGA, // 320x240
FRAMESIZE_CIF, // 400x296
FRAMESIZE_HVGA, // 480x320
FRAMESIZE_VGA, // 640x480
FRAMESIZE_SVGA, // 800x600
FRAMESIZE_XGA, // 1024x768
FRAMESIZE_HD, // 1280x720
FRAMESIZE_SXGA, // 1280x1024
FRAMESIZE_UXGA, // 1600x1200
// 3MP Sensors
FRAMESIZE_FHD, // 1920x1080
FRAMESIZE_P_HD, // 720x1280
FRAMESIZE_P_3MP, // 864x1536
FRAMESIZE_QXGA, // 2048x1536
// 5MP Sensors
FRAMESIZE_QHD, // 2560x1440
FRAMESIZE_WQXGA, // 2560x1600
FRAMESIZE_P_FHD, // 1080x1920
FRAMESIZE_QSXGA, // 2560x1920
FRAMESIZE_INVALID
} framesize_t;
typedef enum {
ASPECT_RATIO_4X3,
ASPECT_RATIO_3X2,
ASPECT_RATIO_16X10,
ASPECT_RATIO_5X3,
ASPECT_RATIO_16X9,
ASPECT_RATIO_21X9,
ASPECT_RATIO_5X4,
ASPECT_RATIO_1X1,
ASPECT_RATIO_9X16
} aspect_ratio_t;
typedef enum {
GAINCEILING_2X,
GAINCEILING_4X,
GAINCEILING_8X,
GAINCEILING_16X,
GAINCEILING_32X,
GAINCEILING_64X,
GAINCEILING_128X,
} gainceiling_t;
typedef struct {
uint16_t max_width;
uint16_t max_height;
uint16_t start_x;
uint16_t start_y;
uint16_t end_x;
uint16_t end_y;
uint16_t offset_x;
uint16_t offset_y;
uint16_t total_x;
uint16_t total_y;
} ratio_settings_t;
typedef struct {
const uint16_t width;
const uint16_t height;
const aspect_ratio_t aspect_ratio;
} resolution_info_t;
// Resolution table (in sensor.c)
extern const resolution_info_t resolution[];
typedef struct {
uint8_t MIDH;
uint8_t MIDL;
uint8_t PID;
uint8_t VER;
} sensor_id_t;
typedef struct {
framesize_t framesize;//0 - 10
bool scale;
bool binning;
uint8_t quality;//0 - 63
int8_t brightness;//-2 - 2
int8_t contrast;//-2 - 2
int8_t saturation;//-2 - 2
int8_t sharpness;//-2 - 2
uint8_t denoise;
uint8_t special_effect;//0 - 6
uint8_t wb_mode;//0 - 4
uint8_t awb;
uint8_t awb_gain;
uint8_t aec;
uint8_t aec2;
int8_t ae_level;//-2 - 2
uint16_t aec_value;//0 - 1200
uint8_t agc;
uint8_t agc_gain;//0 - 30
uint8_t gainceiling;//0 - 6
uint8_t bpc;
uint8_t wpc;
uint8_t raw_gma;
uint8_t lenc;
uint8_t hmirror;
uint8_t vflip;
uint8_t dcw;
uint8_t colorbar;
} camera_status_t;
typedef struct _sensor sensor_t;
typedef struct _sensor {
sensor_id_t id; // Sensor ID.
uint8_t slv_addr; // Sensor I2C slave address.
pixformat_t pixformat;
camera_status_t status;
int xclk_freq_hz;
// Sensor function pointers
int (*init_status) (sensor_t *sensor);
int (*reset) (sensor_t *sensor);
int (*set_pixformat) (sensor_t *sensor, pixformat_t pixformat);
int (*set_framesize) (sensor_t *sensor, framesize_t framesize);
int (*set_contrast) (sensor_t *sensor, int level);
int (*set_brightness) (sensor_t *sensor, int level);
int (*set_saturation) (sensor_t *sensor, int level);
int (*set_sharpness) (sensor_t *sensor, int level);
int (*set_denoise) (sensor_t *sensor, int level);
int (*set_gainceiling) (sensor_t *sensor, gainceiling_t gainceiling);
int (*set_quality) (sensor_t *sensor, int quality);
int (*set_colorbar) (sensor_t *sensor, int enable);
int (*set_whitebal) (sensor_t *sensor, int enable);
int (*set_gain_ctrl) (sensor_t *sensor, int enable);
int (*set_exposure_ctrl) (sensor_t *sensor, int enable);
int (*set_hmirror) (sensor_t *sensor, int enable);
int (*set_vflip) (sensor_t *sensor, int enable);
int (*set_aec2) (sensor_t *sensor, int enable);
int (*set_awb_gain) (sensor_t *sensor, int enable);
int (*set_agc_gain) (sensor_t *sensor, int gain);
int (*set_aec_value) (sensor_t *sensor, int gain);
int (*set_special_effect) (sensor_t *sensor, int effect);
int (*set_wb_mode) (sensor_t *sensor, int mode);
int (*set_ae_level) (sensor_t *sensor, int level);
int (*set_dcw) (sensor_t *sensor, int enable);
int (*set_bpc) (sensor_t *sensor, int enable);
int (*set_wpc) (sensor_t *sensor, int enable);
int (*set_raw_gma) (sensor_t *sensor, int enable);
int (*set_lenc) (sensor_t *sensor, int enable);
int (*get_reg) (sensor_t *sensor, int reg, int mask);
int (*set_reg) (sensor_t *sensor, int reg, int mask, int value);
int (*set_res_raw) (sensor_t *sensor, int startX, int startY, int endX, int endY, int offsetX, int offsetY, int totalX, int totalY, int outputX, int outputY, bool scale, bool binning);
int (*set_pll) (sensor_t *sensor, int bypass, int mul, int sys, int root, int pre, int seld5, int pclken, int pclk);
int (*set_xclk) (sensor_t *sensor, int timer, int xclk);
} sensor_t;
#endif /* __SENSOR_H__ */

View File

@@ -0,0 +1,175 @@
#include "server_camera.h"
#include <string>
#include "string.h"
#include "esp_camera.h"
#include "ClassControllCamera.h"
#include "ClassLogFile.h"
#define SCRATCH_BUFSIZE2 8192
char scratch2[SCRATCH_BUFSIZE2];
esp_err_t handler_lightOn(httpd_req_t *req)
{
LogFile.WriteToFile("handler_lightOn");
printf("handler_lightOn uri:\n"); printf(req->uri); printf("\n");
Camera.LightOnOff(true);
const char* resp_str = (const char*) req->user_ctx;
httpd_resp_send(req, resp_str, strlen(resp_str));
return ESP_OK;
};
esp_err_t handler_lightOff(httpd_req_t *req)
{
LogFile.WriteToFile("handler_lightOff");
printf("handler_lightOff uri:\n"); printf(req->uri); printf("\n");
Camera.LightOnOff(false);
const char* resp_str = (const char*) req->user_ctx;
httpd_resp_send(req, resp_str, strlen(resp_str));
return ESP_OK;
};
esp_err_t handler_capture(httpd_req_t *req)
{
LogFile.WriteToFile("handler_capture");
int quality;
framesize_t res;
Camera.GetCameraParameter(req, quality, res);
printf("Size: %d", res); printf(" Quality: %d\n", quality);
Camera.SetQualitySize(quality, res);
esp_err_t ressult;
ressult = Camera.CaptureToHTTP(req);
return ressult;
};
esp_err_t handler_capture_with_ligth(httpd_req_t *req)
{
LogFile.WriteToFile("handler_capture_with_ligth");
char _query[100];
char _delay[10];
int quality;
framesize_t res;
int delay = 2500;
if (httpd_req_get_url_query_str(req, _query, 100) == ESP_OK)
{
printf("Query: "); printf(_query); printf("\n");
if (httpd_query_key_value(_query, "delay", _delay, 10) == ESP_OK)
{
printf("Delay: "); printf(_delay); printf("\n");
delay = atoi(_delay);
if (delay < 0)
delay = 0;
}
};
Camera.GetCameraParameter(req, quality, res);
printf("Size: %d", res); printf(" Quality: %d\n", quality);
Camera.SetQualitySize(quality, res);
Camera.LightOnOff(true);
const TickType_t xDelay = delay / portTICK_PERIOD_MS;
vTaskDelay( xDelay );
esp_err_t ressult;
ressult = Camera.CaptureToHTTP(req);
Camera.LightOnOff(false);
return ressult;
};
esp_err_t handler_capture_save_to_file(httpd_req_t *req)
{
LogFile.WriteToFile("handler_capture_save_to_file");
char _query[100];
char _delay[10];
int delay = 0;
char filename[100];
std::string fn = "/sdcard/";
int quality;
framesize_t res;
if (httpd_req_get_url_query_str(req, _query, 100) == ESP_OK)
{
printf("Query: "); printf(_query); printf("\n");
if (httpd_query_key_value(_query, "filename", filename, 100) == ESP_OK)
{
fn.append(filename);
printf("Filename: "); printf(fn.c_str()); printf("\n");
}
else
fn.append("noname.jpg");
if (httpd_query_key_value(_query, "delay", _delay, 10) == ESP_OK)
{
printf("Delay: "); printf(_delay); printf("\n");
delay = atoi(_delay);
if (delay < 0)
delay = 0;
}
}
else
fn.append("noname.jpg");
Camera.GetCameraParameter(req, quality, res);
printf("Size: %d", res); printf(" Quality: %d\n", quality);
Camera.SetQualitySize(quality, res);
esp_err_t ressult;
ressult = Camera.CaptureToFile(fn, delay);
const char* resp_str = (const char*) fn.c_str();
httpd_resp_send(req, resp_str, strlen(resp_str));
return ressult;
};
void register_server_camera_uri(httpd_handle_t server)
{
ESP_LOGI(TAGPARTCAMERA, "server_part_camera - Registering URI handlers");
httpd_uri_t camuri = { };
camuri.method = HTTP_GET;
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 = "/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_ligth;
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);
}

View File

@@ -0,0 +1,14 @@
#ifndef JOMJOL_CONTROLCAMERA_H
#define JOMJOL_CONTROLCAMERA_H
#include <esp_log.h>
#include <esp_http_server.h>
//#include "ClassControllCamera.h"
static const char *TAGPARTCAMERA = "server_camera";
void register_server_camera_uri(httpd_handle_t server);
#endif