July 2021 update

master
Anatoli Arkhipenko 3 years ago
parent 82534e2e02
commit ca6babbd7c

@ -5,13 +5,13 @@
**Updated on 2021-03-03:**
**Updated on 2021-07-01:**
- Recompiled with ESP32 Arduino Core 1.0.5
- OP updated to account for recent repo changes by Espressif
- Updated with latest ESP CAM drivers
- Recompiled with ESP32 Arduino Core 1.0.6
- Added vertical flip capability
- Updated with latest ESP CAM drivers
@ -41,13 +41,17 @@ All captured frames are stored in PSRAM (until you run out of memory) and served
1. Download latest ZIP file from https://github.com/espressif/esp32-camera.git into the esp32-cam subfolder
2. Delete `examples` folder from the archive
2. Delete `examples` and `test` folders from the archive
3. Delete **ALL FILES** in the sketch folder except `esp32-cam*.ino` and `camera_pins.h`
4. In the archive subfolder `esp32-camera-master/target` delete subfolders for `esp32s2` and `esp32s3` - I have not tested with those ones
3. unzip using `unzip -j esp32-cam-master.zip` command. This will place all files in the same folder
5. unzip using `unzip -jo esp32-camera-master.zip` command. This will place all files in the same folder
**NOTE:** please observe the `-j` flag: the sketch assumes all files are in the same folder.
**NOTE:** please observe the `-jo` flag: the sketch assumes all files are in the same folder and will overwrite the existing old files without asking for confirmation.

@ -0,0 +1,61 @@
if(IDF_TARGET STREQUAL "esp32" OR IDF_TARGET STREQUAL "esp32s2" OR IDF_TARGET STREQUAL "esp32s3")
set(COMPONENT_SRCS
driver/esp_camera.c
driver/cam_hal.c
driver/sccb.c
driver/sensor.c
sensors/ov2640.c
sensors/ov3660.c
sensors/ov5640.c
sensors/ov7725.c
sensors/ov7670.c
sensors/nt99141.c
conversions/yuv.c
conversions/to_jpg.cpp
conversions/to_bmp.c
conversions/jpge.cpp
conversions/esp_jpg_decode.c
)
set(COMPONENT_ADD_INCLUDEDIRS
driver/include
conversions/include
)
set(COMPONENT_PRIV_INCLUDEDIRS
driver/private_include
sensors/private_include
conversions/private_include
target/private_include
)
if(IDF_TARGET STREQUAL "esp32")
list(APPEND COMPONENT_SRCS
target/xclk.c
target/esp32/ll_cam.c
)
endif()
if(IDF_TARGET STREQUAL "esp32s2")
list(APPEND COMPONENT_SRCS
target/xclk.c
target/esp32s2/ll_cam.c
target/esp32s2/tjpgd.c
)
list(APPEND COMPONENT_PRIV_INCLUDEDIRS
target/esp32s2/private_include
)
endif()
if(IDF_TARGET STREQUAL "esp32s3")
list(APPEND COMPONENT_SRCS
target/esp32s3/ll_cam.c
)
endif()
set(COMPONENT_REQUIRES driver)
set(COMPONENT_PRIV_REQUIRES freertos nvs_flash)
register_component()
endif()

@ -1,65 +1,71 @@
menu "Camera configuration"
config OV2640_SUPPORT
bool "OV2640 Support"
default y
help
Enable this option if you want to use the OV2640.
Disable this option to save memory.
config OV7725_SUPPORT
bool "OV7725 Support"
default n
help
Enable this option if you want to use the OV7725.
Disable this option to save memory.
config OV3660_SUPPORT
bool "OV3660 Support"
default y
help
Enable this option if you want to use the OV3360.
Disable this option to save memory.
config OV5640_SUPPORT
bool "OV5640 Support"
default y
help
Enable this option if you want to use the OV5640.
Disable this option to save memory.
config SCCB_HARDWARE_I2C
bool "Use hardware I2C for SCCB"
default y
help
Enable this option if you want to use hardware I2C to control the camera.
Disable this option to use software I2C.
choice SCCB_HARDWARE_I2C_PORT
bool "I2C peripheral to use for SCCB"
depends on SCCB_HARDWARE_I2C
default SCCB_HARDWARE_I2C_PORT1
config OV7670_SUPPORT
bool "Support OV7670 VGA"
default y
help
Enable this option if you want to use the OV7670.
Disable this option to save memory.
config SCCB_HARDWARE_I2C_PORT0
bool "I2C0"
config SCCB_HARDWARE_I2C_PORT1
bool "I2C1"
config OV7725_SUPPORT
bool "Support OV7725 SVGA"
default n
help
Enable this option if you want to use the OV7725.
Disable this option to save memory.
endchoice
config NT99141_SUPPORT
bool "Support NT99141 HD"
default y
help
Enable this option if you want to use the NT99141.
Disable this option to save memory.
choice CAMERA_TASK_PINNED_TO_CORE
bool "Camera task pinned to core"
default CAMERA_CORE0
help
Pin the camera handle task to a certain core(0/1). It can also be done automatically choosing NO_AFFINITY.
config OV2640_SUPPORT
bool "Support OV2640 2MP"
default y
help
Enable this option if you want to use the OV2640.
Disable this option to save memory.
config CAMERA_CORE0
bool "CORE0"
config CAMERA_CORE1
bool "CORE1"
config CAMERA_NO_AFFINITY
bool "NO_AFFINITY"
config OV3660_SUPPORT
bool "Support OV3660 3MP"
default y
help
Enable this option if you want to use the OV3360.
Disable this option to save memory.
config OV5640_SUPPORT
bool "Support OV5640 5MP"
default y
help
Enable this option if you want to use the OV5640.
Disable this option to save memory.
choice SCCB_HARDWARE_I2C_PORT
bool "I2C peripheral to use for SCCB"
default SCCB_HARDWARE_I2C_PORT1
config SCCB_HARDWARE_I2C_PORT0
bool "I2C0"
config SCCB_HARDWARE_I2C_PORT1
bool "I2C1"
endchoice
choice CAMERA_TASK_PINNED_TO_CORE
bool "Camera task pinned to core"
default CAMERA_CORE0
help
Pin the camera handle task to a certain core(0/1). It can also be done automatically choosing NO_AFFINITY.
config CAMERA_CORE0
bool "CORE0"
config CAMERA_CORE1
bool "CORE1"
config CAMERA_NO_AFFINITY
bool "NO_AFFINITY"
endchoice
endchoice
endmenu

@ -1,16 +1,358 @@
# ESP32 MJPEG Multiclient Streaming All Frames Server
# ESP32 Camera Driver
This is a MJPEG streaming webserver implemented for AI-Thinker ESP32-CAM or ESP-EYE modules.
## General Information
This is tested to work with **VLC** and **Blynk** video widget.
This repository hosts ESP32, ESP32-S2 and ESP32-S3 compatible driver for OV2640, OV3660, OV5640, OV7670 and OV7725 image sensors. Additionally it provides a few tools, which allow converting the captured frame data to the more common BMP and JPEG formats.
## Important to Remember
- Except when using CIF or lower resolution with JPEG, the driver requires PSRAM to be installed and activated.
- Using YUV or RGB puts a lot of strain on the chip because writing to PSRAM is not particularly fast. The result is that image data might be missing. This is particularly true if WiFi is enabled. If you need RGB data, it is recommended that JPEG is captured and then turned into RGB using `fmt2rgb888` or `fmt2bmp`/`frame2bmp`.
- When 1 frame buffer is used, the driver will wait for the current frame to finish (VSYNC) and start I2S DMA. After the frame is acquired, I2S will be stopped and the frame buffer returned to the application. This approach gives more control over the system, but results in longer time to get the frame.
- When 2 or more frame bufers are used, I2S is running in continuous mode and each frame is pushed to a queue that the application can access. This approach puts more strain on the CPU/Memory, but allows for double the frame rate. Please use only with JPEG.
**This version uses FreeRTOS tasks to enable streaming to up to 10 connected clients and is buffering and sending every frame to every client**
## Installation Instructions
### Using esp-idf
Inspired by and based on this Instructable: [$9 RTSP Video Streamer Using the ESP32-CAM Board](https://www.instructables.com/id/9-RTSP-Video-Streamer-Using-the-ESP32-CAM-Board/)
- Clone or download and extract the repository to the components folder of your ESP-IDF project
- Enable PSRAM in `menuconfig` (also set Flash and PSRAM frequiencies to 80MHz)
- Include `esp_camera.h` in your code
### Using PlatformIO
The easy way -- on the `env` section of `platformio.ini`, add the following:
```ini
[env]
lib_deps =
esp32-camera
```
Now the `esp_camera.h` is available to be included:
```c
#include "esp_camera.h"
```
Enable PSRAM on `menuconfig` or type it direclty on `sdkconfig`. Check the [official doc](https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-reference/kconfig.html#config-esp32-spiram-support) for more info.
```
CONFIG_ESP32_SPIRAM_SUPPORT=y
```
***Arduino*** The easy-way (content above) only seems to work if you're using `framework=arduino` which seems to take a bunch of the guesswork out (thanks Arduino!) but also suck up a lot more memory and flash, almost crippling the performance. If you plan to use the `framework=espidf` then read the sections below carefully!!
## Platform.io lib/submodule (for framework=espidf)
It's probably easier to just skip the platform.io library registry version and link the git repo as a submodule. (i.e. using code outside the platform.io library management). In this example we will install this as a submodule inside the platform.io $project/lib folder:
```
cd $project\lib
git submodule add -b master https://github.com/espressif/esp32-camera.git
```
Then in `platformio.ini` file
```
build_flags =
-I../lib/esp32-camera
```
After that `#include "esp_camera.h"` statement will be available. Now the module is included, and you're hopefully back to the same place as the easy-Arduino way.
**Warning about platform.io/espidf and fresh (not initialized) git repos**
There is a sharp-edge on you'll discover in the platform.io build process (in espidf v3.3 & 4.0.1) where a project which has only had `git init` but nothing committed will crash platform.io build process with highly non-useful output. The cause is due to lack of a version (making you think you did something wrong, when you didn't at all) - the output is horribly non-descript. Solution: the devs want you to create a file called version.txt with a number in it, or simply commit any file to the projects git repo and use git. This happens because platform.io build process tries to be too clever and determine the build version number from the git repo - it's a sharp edge you'll only encounter if you're experimenting on a new project with no commits .. like wtf is my camera not working let's try a 'clean project'?! </rant>
## Platform.io Kconfig
Kconfig is used by the platform.io menuconfig (accessed by running: `pio run -t menuconfig`) to interactively manage the various #ifdef statements throughout the espidf and supporting libraries (i.e. this repo: esp32-camera and arduino-esp32.git). The menuconfig process generates the `sdkconfig` file which is ultimately used behind the scenes by espidf compile+build process.
**Make sure to append or symlink** [this `Kconfig`](./Kconfig) content into the `Kconfig` of your project.
You symlink (or copy) the included Kconfig into your platform.io projects src directory. The file should be named `Kconfig.projbuild` in your projects src\ directory or you could also add the library path to a CMakefile.txt and hope the `Kconfig` (or `Kconfig.projbuild`) gets discovered by the menuconfig process, though this unpredictable for me.
The unpredictable wonky behavior in platform.io build process around Kconfig naming (Kconfig vs. Kconfig.projbuild) occurs between espidf versions 3.3 and 4.0 - but if you don't see "Camera configuration" in your `pio run -t menuconfig` then there is no point trying to test camera code (it may compile, but it probably won't work!) and it seems the platform.io devs (when they built their wrapper around the espidf menuconfig) didn't implement it properly. You've probably already figured out you can't use the espidf build tools since the files are in totally different locations and also different versions with sometimes different syntax. This is one of those times you might consider changing the `platformio.ini` from `platform=espressif32` to `platform=https://github.com/platformio/platform-espressif32.git#develop` to get a more recent version of the espidf 4.0 tools.
However with a bit of patience and experimenting you'll figure the Kconfig out. Once Kconfig (or Kconfig.projbuild) is working then you will be able to choose the configurations according to your setup or the camera libraries will be compiled. Although you might also need to delete your .pio/build directory before the options appear .. again, the `pio run -t menuconfig` doens't always notice the new Kconfig files!
If you miss-skip-ignore this critical step the camera module will compile but camera logic inside the library will be 'empty' because the Kconfig sets the proper #ifdef statements during the build process to initialize the selected cameras. It's very not optional!
### Kconfig options
| config | description | default |
| --------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------ |
| CONFIG_OV2640_SUPPORT | Support for OV2640 camera | enabled |
| CONFIG_OV7725_SUPPORT | Support for OV7725 camera | disabled |
| CONFIG_OV3660_SUPPORT | Support for OV3660 camera | enabled |
| CONFIG_OV5640_SUPPORT | Support for OV5640 camera | enabled |
| CONFIG_SCCB_HARDWARE_I2C | Enable this option if you want to use hardware I2C to control the camera. Disable this option to use software I2C. | enabled |
| CONFIG_SCCB_HARDWARE_I2C_PORT | I2C peripheral to use for SCCB. Can be I2C0 and I2C1. | CONFIG_SCCB_HARDWARE_I2C_PORT1 |
| CONFIG_CAMERA_TASK_PINNED_TO_CORE | Pin the camera handle task to a certain core(0/1). It can also be done automatically choosing NO_AFFINITY. Can be CAMERA_CORE0, CAMERA_CORE1 or NO_AFFINITY. | CONFIG_CAMERA_CORE0 |
## Examples
### Initialization
```c
#include "esp_camera.h"
//WROVER-KIT PIN Map
#define CAM_PIN_PWDN -1 //power down is not used
#define CAM_PIN_RESET -1 //software reset will be performed
#define CAM_PIN_XCLK 21
#define CAM_PIN_SIOD 26
#define CAM_PIN_SIOC 27
#define CAM_PIN_D7 35
#define CAM_PIN_D6 34
#define CAM_PIN_D5 39
#define CAM_PIN_D4 36
#define CAM_PIN_D3 19
#define CAM_PIN_D2 18
#define CAM_PIN_D1 5
#define CAM_PIN_D0 4
#define CAM_PIN_VSYNC 25
#define CAM_PIN_HREF 23
#define CAM_PIN_PCLK 22
static camera_config_t camera_config = {
.pin_pwdn = CAM_PIN_PWDN,
.pin_reset = CAM_PIN_RESET,
.pin_xclk = CAM_PIN_XCLK,
.pin_sscb_sda = CAM_PIN_SIOD,
.pin_sscb_scl = CAM_PIN_SIOC,
.pin_d7 = CAM_PIN_D7,
.pin_d6 = CAM_PIN_D6,
.pin_d5 = CAM_PIN_D5,
.pin_d4 = CAM_PIN_D4,
.pin_d3 = CAM_PIN_D3,
.pin_d2 = CAM_PIN_D2,
.pin_d1 = CAM_PIN_D1,
.pin_d0 = CAM_PIN_D0,
.pin_vsync = CAM_PIN_VSYNC,
.pin_href = CAM_PIN_HREF,
.pin_pclk = CAM_PIN_PCLK,
.xclk_freq_hz = 20000000,//EXPERIMENTAL: Set to 16MHz on ESP32-S2 or ESP32-S3 to enable EDMA mode
.ledc_timer = LEDC_TIMER_0,
.ledc_channel = LEDC_CHANNEL_0,
.pixel_format = PIXFORMAT_JPEG,//YUV422,GRAYSCALE,RGB565,JPEG
.frame_size = FRAMESIZE_UXGA,//QQVGA-QXGA Do not use sizes above QVGA when not JPEG
.jpeg_quality = 12, //0-63 lower number means higher quality
.fb_count = 1, //if more than one, i2s runs in continuous mode. Use only with JPEG
.grab_mode = CAMERA_GRAB_WHEN_EMPTY//CAMERA_GRAB_LATEST. Sets when buffers should be filled
};
esp_err_t camera_init(){
//power up the camera if PWDN pin is defined
if(CAM_PIN_PWDN != -1){
pinMode(CAM_PIN_PWDN, OUTPUT);
digitalWrite(CAM_PIN_PWDN, LOW);
}
//initialize the camera
esp_err_t err = esp_camera_init(&camera_config);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Camera Init Failed");
return err;
}
return ESP_OK;
}
esp_err_t camera_capture(){
//acquire a frame
camera_fb_t * fb = esp_camera_fb_get();
if (!fb) {
ESP_LOGE(TAG, "Camera Capture Failed");
return ESP_FAIL;
}
//replace this with your own function
process_image(fb->width, fb->height, fb->format, fb->buf, fb->len);
//return the frame buffer back to the driver for reuse
esp_camera_fb_return(fb);
return ESP_OK;
}
```
### JPEG HTTP Capture
```c
#include "esp_camera.h"
#include "esp_http_server.h"
#include "esp_timer.h"
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;
}
esp_err_t jpg_httpd_handler(httpd_req_t *req){
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(TAG, "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(TAG, "JPG: %uKB %ums", (uint32_t)(fb_len/1024), (uint32_t)((fr_end - fr_start)/1000));
return res;
}
```
### JPEG HTTP Stream
```c
#include "esp_camera.h"
#include "esp_http_server.h"
#include "esp_timer.h"
#define PART_BOUNDARY "123456789000000000000987654321"
static const char* _STREAM_CONTENT_TYPE = "multipart/x-mixed-replace;boundary=" PART_BOUNDARY;
static const char* _STREAM_BOUNDARY = "\r\n--" PART_BOUNDARY "\r\n";
static const char* _STREAM_PART = "Content-Type: image/jpeg\r\nContent-Length: %u\r\n\r\n";
esp_err_t jpg_stream_httpd_handler(httpd_req_t *req){
camera_fb_t * fb = NULL;
esp_err_t res = ESP_OK;
size_t _jpg_buf_len;
uint8_t * _jpg_buf;
char * part_buf[64];
static int64_t last_frame = 0;
if(!last_frame) {
last_frame = esp_timer_get_time();
}
res = httpd_resp_set_type(req, _STREAM_CONTENT_TYPE);
if(res != ESP_OK){
return res;
}
while(true){
fb = esp_camera_fb_get();
if (!fb) {
ESP_LOGE(TAG, "Camera capture failed");
res = ESP_FAIL;
break;
}
if(fb->format != PIXFORMAT_JPEG){
bool jpeg_converted = frame2jpg(fb, 80, &_jpg_buf, &_jpg_buf_len);
if(!jpeg_converted){
ESP_LOGE(TAG, "JPEG compression failed");
esp_camera_fb_return(fb);
res = ESP_FAIL;
}
} else {
_jpg_buf_len = fb->len;
_jpg_buf = fb->buf;
}
if(res == ESP_OK){
res = httpd_resp_send_chunk(req, _STREAM_BOUNDARY, strlen(_STREAM_BOUNDARY));
}
if(res == ESP_OK){
size_t hlen = snprintf((char *)part_buf, 64, _STREAM_PART, _jpg_buf_len);
res = httpd_resp_send_chunk(req, (const char *)part_buf, hlen);
}
if(res == ESP_OK){
res = httpd_resp_send_chunk(req, (const char *)_jpg_buf, _jpg_buf_len);
}
if(fb->format != PIXFORMAT_JPEG){
free(_jpg_buf);
}
esp_camera_fb_return(fb);
if(res != ESP_OK){
break;
}
int64_t fr_end = esp_timer_get_time();
int64_t frame_time = fr_end - last_frame;
last_frame = fr_end;
frame_time /= 1000;
ESP_LOGI(TAG, "MJPG: %uKB %ums (%.1ffps)",
(uint32_t)(_jpg_buf_len/1024),
(uint32_t)frame_time, 1000.0 / (uint32_t)frame_time);
}
last_frame = 0;
return res;
}
```
### BMP HTTP Capture
```c
#include "esp_camera.h"
#include "esp_http_server.h"
#include "esp_timer.h"
esp_err_t bmp_httpd_handler(httpd_req_t *req){
camera_fb_t * fb = NULL;
esp_err_t res = ESP_OK;
int64_t fr_start = esp_timer_get_time();
fb = esp_camera_fb_get();
if (!fb) {
ESP_LOGE(TAG, "Camera capture failed");
httpd_resp_send_500(req);
return ESP_FAIL;
}
uint8_t * buf = NULL;
size_t buf_len = 0;
bool converted = frame2bmp(fb, &buf, &buf_len);
esp_camera_fb_return(fb);
if(!converted){
ESP_LOGE(TAG, "BMP conversion failed");
httpd_resp_send_500(req);
return ESP_FAIL;
}
res = httpd_resp_set_type(req, "image/x-windows-bmp")
|| httpd_resp_set_hdr(req, "Content-Disposition", "inline; filename=capture.bmp")
|| httpd_resp_send(req, (const char *)buf, buf_len);
free(buf);
int64_t fr_end = esp_timer_get_time();
ESP_LOGI(TAG, "BMP: %uKB %ums", (uint32_t)(buf_len/1024), (uint32_t)((fr_end - fr_start)/1000));
return res;
}
```

@ -0,0 +1,472 @@
// Copyright 2010-2020 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.
#include <stdio.h>
#include <string.h>
#include "esp_heap_caps.h"
#include "ll_cam.h"
#include "cam_hal.h"
static const char *TAG = "cam_hal";
static cam_obj_t *cam_obj = NULL;
static const uint32_t JPEG_SOI_MARKER = 0xFFD8FF; // written in little-endian for esp32
static const uint16_t JPEG_EOI_MARKER = 0xD9FF; // written in little-endian for esp32
static int cam_verify_jpeg_soi(const uint8_t *inbuf, uint32_t length)
{
uint32_t sig = *((uint32_t *)inbuf) & 0xFFFFFF;
if(sig != JPEG_SOI_MARKER) {
for (uint32_t i = 0; i < length; i++) {
sig = *((uint32_t *)(&inbuf[i])) & 0xFFFFFF;
if (sig == JPEG_SOI_MARKER) {
ESP_LOGW(TAG, "SOI: %d", i);
return i;
}
}
ESP_LOGW(TAG, "NO-SOI");
return -1;
}
return 0;
}
static int cam_verify_jpeg_eoi(const uint8_t *inbuf, uint32_t length)
{
int offset = -1;
uint8_t *dptr = (uint8_t *)inbuf + length - 2;
while (dptr > inbuf) {
uint16_t sig = *((uint16_t *)dptr);
if (JPEG_EOI_MARKER == sig) {
offset = dptr - inbuf;
//ESP_LOGW(TAG, "EOI: %d", length - (offset + 2));
return offset;
}
dptr--;
}
return -1;
}
static bool cam_get_next_frame(int * frame_pos)
{
if(!cam_obj->frames[*frame_pos].en){
for (int x = 0; x < cam_obj->frame_cnt; x++) {
if (cam_obj->frames[x].en) {
*frame_pos = x;
return true;
}
}
} else {
return true;
}
return false;
}
static bool cam_start_frame(int * frame_pos)
{
if (cam_get_next_frame(frame_pos)) {
if(ll_cam_start(cam_obj, *frame_pos)){
// Vsync the frame manually
ll_cam_do_vsync(cam_obj);
uint64_t us = (uint64_t)esp_timer_get_time();
cam_obj->frames[*frame_pos].fb.timestamp.tv_sec = us / 1000000UL;
cam_obj->frames[*frame_pos].fb.timestamp.tv_usec = us % 1000000UL;
return true;
}
}
return false;
}
void IRAM_ATTR ll_cam_send_event(cam_obj_t *cam, cam_event_t cam_event, BaseType_t * HPTaskAwoken)
{
if (xQueueSendFromISR(cam->event_queue, (void *)&cam_event, HPTaskAwoken) != pdTRUE) {
ll_cam_stop(cam);
cam->state = CAM_STATE_IDLE;
ESP_EARLY_LOGE(TAG, "EV-OVF");
}
}
//Copy fram from DMA dma_buffer to fram dma_buffer
static void cam_task(void *arg)
{
int cnt = 0;
int frame_pos = 0;
cam_obj->state = CAM_STATE_IDLE;
cam_event_t cam_event = 0;
xQueueReset(cam_obj->event_queue);
while (1) {
xQueueReceive(cam_obj->event_queue, (void *)&cam_event, portMAX_DELAY);
DBG_PIN_SET(1);
switch (cam_obj->state) {
case CAM_STATE_IDLE: {
if (cam_event == CAM_VSYNC_EVENT) {
//DBG_PIN_SET(1);
if(cam_start_frame(&frame_pos)){
cam_obj->frames[frame_pos].fb.len = 0;
cam_obj->state = CAM_STATE_READ_BUF;
}
cnt = 0;
}
}
break;
case CAM_STATE_READ_BUF: {
camera_fb_t * frame_buffer_event = &cam_obj->frames[frame_pos].fb;
size_t pixels_per_dma = (cam_obj->dma_half_buffer_size * cam_obj->fb_bytes_per_pixel) / (cam_obj->dma_bytes_per_item * cam_obj->in_bytes_per_pixel);
if (cam_event == CAM_IN_SUC_EOF_EVENT) {
if(!cam_obj->psram_mode){
if (cam_obj->fb_size < (frame_buffer_event->len + pixels_per_dma)) {
ESP_LOGW(TAG, "FB-OVF");
ll_cam_stop(cam_obj);
DBG_PIN_SET(0);
continue;
}
frame_buffer_event->len += ll_cam_memcpy(cam_obj,
&frame_buffer_event->buf[frame_buffer_event->len],
&cam_obj->dma_buffer[(cnt % cam_obj->dma_half_buffer_cnt) * cam_obj->dma_half_buffer_size],
cam_obj->dma_half_buffer_size);
}
//Check for JPEG SOI in the first buffer. stop if not found
if (cam_obj->jpeg_mode && cnt == 0 && cam_verify_jpeg_soi(frame_buffer_event->buf, frame_buffer_event->len) != 0) {
ll_cam_stop(cam_obj);
cam_obj->state = CAM_STATE_IDLE;
}
cnt++;
} else if (cam_event == CAM_VSYNC_EVENT) {
//DBG_PIN_SET(1);
ll_cam_stop(cam_obj);
if (cnt || !cam_obj->jpeg_mode || cam_obj->psram_mode) {
if (cam_obj->jpeg_mode) {
if (!cam_obj->psram_mode) {
if (cam_obj->fb_size < (frame_buffer_event->len + pixels_per_dma)) {
ESP_LOGW(TAG, "FB-OVF");
cnt--;
} else {
frame_buffer_event->len += ll_cam_memcpy(cam_obj,
&frame_buffer_event->buf[frame_buffer_event->len],
&cam_obj->dma_buffer[(cnt % cam_obj->dma_half_buffer_cnt) * cam_obj->dma_half_buffer_size],
cam_obj->dma_half_buffer_size);
}
}
cnt++;
}
cam_obj->frames[frame_pos].en = 0;
if (cam_obj->psram_mode) {
if (cam_obj->jpeg_mode) {
frame_buffer_event->len = cnt * cam_obj->dma_half_buffer_size;
} else {
frame_buffer_event->len = cam_obj->recv_size;
}
} else if (!cam_obj->jpeg_mode) {
if (frame_buffer_event->len != cam_obj->fb_size) {
cam_obj->frames[frame_pos].en = 1;
ESP_LOGE(TAG, "FB-SIZE: %u != %u", frame_buffer_event->len, cam_obj->fb_size);
}
}
//send frame
if(!cam_obj->frames[frame_pos].en && xQueueSend(cam_obj->frame_buffer_queue, (void *)&frame_buffer_event, 0) != pdTRUE) {
//pop frame buffer from the queue
camera_fb_t * fb2 = NULL;
if(xQueueReceive(cam_obj->frame_buffer_queue, &fb2, 0) == pdTRUE) {
//push the new frame to the end of the queue
if (xQueueSend(cam_obj->frame_buffer_queue, (void *)&frame_buffer_event, 0) != pdTRUE) {
cam_obj->frames[frame_pos].en = 1;
ESP_LOGE(TAG, "FBQ-SND");
}
//free the popped buffer
cam_give(fb2);
} else {
//queue is full and we could not pop a frame from it
cam_obj->frames[frame_pos].en = 1;
ESP_LOGE(TAG, "FBQ-RCV");
}
}
}
if(!cam_start_frame(&frame_pos)){
cam_obj->state = CAM_STATE_IDLE;
} else {
cam_obj->frames[frame_pos].fb.len = 0;
}
cnt = 0;
}
}
break;
}
DBG_PIN_SET(0);
}
}
static lldesc_t * allocate_dma_descriptors(uint32_t count, uint16_t size, uint8_t * buffer)
{
lldesc_t *dma = (lldesc_t *)heap_caps_malloc(count * sizeof(lldesc_t), MALLOC_CAP_DMA);
if (dma == NULL) {
return dma;
}
for (int x = 0; x < count; x++) {
dma[x].size = size;
dma[x].length = 0;
dma[x].sosf = 0;
dma[x].eof = 0;
dma[x].owner = 1;
dma[x].buf = (buffer + size * x);
dma[x].empty = (uint32_t)&dma[(x + 1) % count];
}
return dma;
}
static esp_err_t cam_dma_config()
{
bool ret = ll_cam_dma_sizes(cam_obj);
if (0 == ret) {
return ESP_FAIL;
}
cam_obj->dma_node_cnt = (cam_obj->dma_buffer_size) / cam_obj->dma_node_buffer_size; // Number of DMA nodes
cam_obj->frame_copy_cnt = cam_obj->recv_size / cam_obj->dma_half_buffer_size; // Number of interrupted copies, ping-pong copy
ESP_LOGI(TAG, "buffer_size: %d, half_buffer_size: %d, node_buffer_size: %d, node_cnt: %d, total_cnt: %d",
cam_obj->dma_buffer_size, cam_obj->dma_half_buffer_size, cam_obj->dma_node_buffer_size, cam_obj->dma_node_cnt, cam_obj->frame_copy_cnt);
cam_obj->dma_buffer = NULL;
cam_obj->dma = NULL;
cam_obj->frames = (cam_frame_t *)heap_caps_calloc(1, cam_obj->frame_cnt * sizeof(cam_frame_t), MALLOC_CAP_DEFAULT);
CAM_CHECK(cam_obj->frames != NULL, "frames malloc failed", ESP_FAIL);
uint8_t dma_align = 0;
size_t fb_size = cam_obj->fb_size;
if (cam_obj->psram_mode) {
dma_align = ll_cam_get_dma_align(cam_obj);
if (cam_obj->fb_size < cam_obj->recv_size) {
fb_size = cam_obj->recv_size;
}
}
for (int x = 0; x < cam_obj->frame_cnt; x++) {
cam_obj->frames[x].dma = NULL;
cam_obj->frames[x].fb_offset = 0;
cam_obj->frames[x].en = 0;
cam_obj->frames[x].fb.buf = (uint8_t *)heap_caps_malloc(fb_size * sizeof(uint8_t) + dma_align, MALLOC_CAP_SPIRAM);
CAM_CHECK(cam_obj->frames[x].fb.buf != NULL, "frame buffer malloc failed", ESP_FAIL);
if (cam_obj->psram_mode) {
//align PSRAM buffer. TODO: save the offset so proper address can be freed later
cam_obj->frames[x].fb_offset = dma_align - ((uint32_t)cam_obj->frames[x].fb.buf & (dma_align - 1));
cam_obj->frames[x].fb.buf += cam_obj->frames[x].fb_offset;
ESP_LOGI(TAG, "Frame[%d]: Offset: %u, Addr: 0x%08X", x, cam_obj->frames[x].fb_offset, (uint32_t)cam_obj->frames[x].fb.buf);
cam_obj->frames[x].dma = allocate_dma_descriptors(cam_obj->dma_node_cnt, cam_obj->dma_node_buffer_size, cam_obj->frames[x].fb.buf);
CAM_CHECK(cam_obj->frames[x].dma != NULL, "frame dma malloc failed", ESP_FAIL);
}
cam_obj->frames[x].en = 1;
}
if (!cam_obj->psram_mode) {
cam_obj->dma_buffer = (uint8_t *)heap_caps_malloc(cam_obj->dma_buffer_size * sizeof(uint8_t), MALLOC_CAP_DMA);
CAM_CHECK(cam_obj->dma_buffer != NULL, "dma_buffer malloc failed", ESP_FAIL);
cam_obj->dma = allocate_dma_descriptors(cam_obj->dma_node_cnt, cam_obj->dma_node_buffer_size, cam_obj->dma_buffer);
CAM_CHECK(cam_obj->dma != NULL, "dma malloc failed", ESP_FAIL);
}
return ESP_OK;
}
esp_err_t cam_init(const camera_config_t *config)
{
CAM_CHECK(NULL != config, "config pointer is invalid", ESP_ERR_INVALID_ARG);
esp_err_t ret = ESP_OK;
cam_obj = (cam_obj_t *)heap_caps_calloc(1, sizeof(cam_obj_t), MALLOC_CAP_DMA);
CAM_CHECK(NULL != cam_obj, "lcd_cam object malloc error", ESP_ERR_NO_MEM);
cam_obj->swap_data = 0;
cam_obj->vsync_pin = config->pin_vsync;
cam_obj->vsync_invert = true;
ll_cam_set_pin(cam_obj, config);
ret = ll_cam_config(cam_obj, config);
CAM_CHECK_GOTO(ret == ESP_OK, "ll_cam initialize failed", err);
#if CAMERA_DBG_PIN_ENABLE
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[DBG_PIN_NUM], PIN_FUNC_GPIO);
gpio_set_direction(DBG_PIN_NUM, GPIO_MODE_OUTPUT);
gpio_set_pull_mode(DBG_PIN_NUM, GPIO_FLOATING);
#endif
ESP_LOGI(TAG, "cam init ok");
return ESP_OK;
err:
free(cam_obj);
cam_obj = NULL;
return ESP_FAIL;
}
esp_err_t cam_config(const camera_config_t *config, framesize_t frame_size, uint8_t sensor_pid)
{
CAM_CHECK(NULL != config, "config pointer is invalid", ESP_ERR_INVALID_ARG);
esp_err_t ret = ESP_OK;
ret = ll_cam_set_sample_mode(cam_obj, (pixformat_t)config->pixel_format, config->xclk_freq_hz, sensor_pid);
cam_obj->jpeg_mode = config->pixel_format == PIXFORMAT_JPEG;
#if CONFIG_IDF_TARGET_ESP32
cam_obj->psram_mode = false;
#else
cam_obj->psram_mode = (config->xclk_freq_hz == 16000000);
#endif
cam_obj->frame_cnt = config->fb_count;
cam_obj->width = resolution[frame_size].width;
cam_obj->height = resolution[frame_size].height;
if(cam_obj->jpeg_mode){
cam_obj->recv_size = cam_obj->width * cam_obj->height / 5;
cam_obj->fb_size = cam_obj->recv_size;
} else {
cam_obj->recv_size = cam_obj->width * cam_obj->height * cam_obj->in_bytes_per_pixel;
cam_obj->fb_size = cam_obj->width * cam_obj->height * cam_obj->fb_bytes_per_pixel;
}
ret = cam_dma_config();
CAM_CHECK_GOTO(ret == ESP_OK, "cam_dma_config failed", err);
cam_obj->event_queue = xQueueCreate(cam_obj->dma_half_buffer_cnt - 1, sizeof(cam_event_t));
CAM_CHECK_GOTO(cam_obj->event_queue != NULL, "event_queue create failed", err);
size_t frame_buffer_queue_len = cam_obj->frame_cnt;
if (config->grab_mode == CAMERA_GRAB_LATEST && cam_obj->frame_cnt > 1) {
frame_buffer_queue_len = cam_obj->frame_cnt - 1;
}
cam_obj->frame_buffer_queue = xQueueCreate(frame_buffer_queue_len, sizeof(camera_fb_t*));
CAM_CHECK_GOTO(cam_obj->frame_buffer_queue != NULL, "frame_buffer_queue create failed", err);
ret = ll_cam_init_isr(cam_obj);
CAM_CHECK_GOTO(ret == ESP_OK, "cam intr alloc failed", err);
#if CONFIG_CAMERA_CORE0
xTaskCreatePinnedToCore(cam_task, "cam_task", 2048, NULL, configMAX_PRIORITIES - 2, &cam_obj->task_handle, 0);
#elif CONFIG_CAMERA_CORE1
xTaskCreatePinnedToCore(cam_task, "cam_task", 2048, NULL, configMAX_PRIORITIES - 2, &cam_obj->task_handle, 1);
#else
xTaskCreate(cam_task, "cam_task", 2048, NULL, configMAX_PRIORITIES - 2, &cam_obj->task_handle);
#endif
ESP_LOGI(TAG, "cam config ok");
return ESP_OK;
err:
cam_deinit();
return ESP_FAIL;
}
esp_err_t cam_deinit(void)
{
if (!cam_obj) {
return ESP_FAIL;
}
cam_stop();
gpio_isr_handler_remove(cam_obj->vsync_pin);
if (cam_obj->task_handle) {
vTaskDelete(cam_obj->task_handle);
}
if (cam_obj->event_queue) {
vQueueDelete(cam_obj->event_queue);
}
if (cam_obj->frame_buffer_queue) {
vQueueDelete(cam_obj->frame_buffer_queue);
}
if (cam_obj->dma) {
free(cam_obj->dma);
}
if (cam_obj->dma_buffer) {
free(cam_obj->dma_buffer);
}
if (cam_obj->frames) {
for (int x = 0; x < cam_obj->frame_cnt; x++) {
free(cam_obj->frames[x].fb.buf - cam_obj->frames[x].fb_offset);
if (cam_obj->frames[x].dma) {
free(cam_obj->frames[x].dma);
}
}
free(cam_obj->frames);
}
if (cam_obj->cam_intr_handle) {
esp_intr_free(cam_obj->cam_intr_handle);
}
free(cam_obj);
cam_obj = NULL;
return ESP_OK;
}
void cam_stop(void)
{
ll_cam_vsync_intr_enable(cam_obj, false);
ll_cam_stop(cam_obj);
}
void cam_start(void)
{
ll_cam_vsync_intr_enable(cam_obj, true);
}
camera_fb_t *cam_take(TickType_t timeout)
{
camera_fb_t *dma_buffer = NULL;
TickType_t start = xTaskGetTickCount();
xQueueReceive(cam_obj->frame_buffer_queue, (void *)&dma_buffer, timeout);
if (dma_buffer) {
if(cam_obj->jpeg_mode){
// find the end marker for JPEG. Data after that can be discarded
int offset_e = cam_verify_jpeg_eoi(dma_buffer->buf, dma_buffer->len);
if (offset_e >= 0) {
// adjust buffer length
dma_buffer->len = offset_e + sizeof(JPEG_EOI_MARKER);
return dma_buffer;
} else {
ESP_LOGW(TAG, "NO-EOI");
cam_give(dma_buffer);
return cam_take(timeout - (xTaskGetTickCount() - start));//recurse!!!!
}
} else if(cam_obj->psram_mode && cam_obj->in_bytes_per_pixel != cam_obj->fb_bytes_per_pixel){
//currently this is used only for YUV to GRAYSCALE
dma_buffer->len = ll_cam_memcpy(cam_obj, dma_buffer->buf, dma_buffer->buf, dma_buffer->len);
}
return dma_buffer;
} else {
ESP_LOGI(TAG, "Failed to get the frame on time!");
}
return NULL;
}
void cam_give(camera_fb_t *dma_buffer)
{
for (int x = 0; x < cam_obj->frame_cnt; x++) {
if (&cam_obj->frames[x].fb == dma_buffer) {
cam_obj->frames[x].en = 1;
break;
}
}
}

@ -0,0 +1,60 @@
// Copyright 2010-2020 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.
#pragma once
#include "esp_camera.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Uninitialize the lcd_cam module
*
* @param handle Provide handle pointer to release resources
*
* @return
* - ESP_OK Success
* - ESP_FAIL Uninitialize fail
*/
esp_err_t cam_deinit(void);
/**
* @brief Initialize the lcd_cam module
*
* @param config Configurations - see lcd_cam_config_t struct
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
* - ESP_ERR_NO_MEM No memory to initialize lcd_cam
* - ESP_FAIL Initialize fail
*/
esp_err_t cam_init(const camera_config_t *config);
esp_err_t cam_config(const camera_config_t *config, framesize_t frame_size, uint8_t sensor_pid);
void cam_stop(void);
void cam_start(void);
camera_fb_t *cam_take(TickType_t timeout);
void cam_give(camera_fb_t *dma_buffer);
#ifdef __cplusplus
}
#endif

File diff suppressed because it is too large Load Diff

@ -15,6 +15,10 @@
#if ESP_IDF_VERSION_MAJOR >= 4 // IDF 4+
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
#include "esp32/rom/lldesc.h"
#elif CONFIG_IDF_TARGET_ESP32S2 // ESP32-S2
#include "esp32s2/rom/lldesc.h"
#elif CONFIG_IDF_TARGET_ESP32S3 // ESP32-S3
#include "esp32s3/rom/lldesc.h"
#else
#error Target CONFIG_IDF_TARGET is not supported
#endif
@ -22,28 +26,3 @@
#include "rom/lldesc.h"
#endif
typedef union {
struct {
uint8_t sample2;
uint8_t unused2;
uint8_t sample1;
uint8_t unused1;
};
uint32_t val;
} dma_elem_t;
typedef enum {
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 s2, 00 s2 00 s3, 00 s3 00 s4, ...
*/
SM_0A0B_0B0C = 0,
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 s2, 00 s3 00 s4, ...
*/
SM_0A0B_0C0D = 1,
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 00, 00 s2 00 00, 00 s3 00 00, ...
*/
SM_0A00_0B00 = 3,
} i2s_sampling_mode_t;

@ -0,0 +1,4 @@
COMPONENT_ADD_INCLUDEDIRS := driver/include conversions/include
COMPONENT_PRIV_INCLUDEDIRS := driver/private_include conversions/private_include sensors/private_include target/private_include
COMPONENT_SRCDIRS := driver conversions sensors target target/esp32
CXXFLAGS += -fno-rtti

@ -0,0 +1,430 @@
// 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.
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include "time.h"
#include "sys/time.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "driver/gpio.h"
#include "esp_system.h"
#include "nvs_flash.h"
#include "nvs.h"
#include "sensor.h"
#include "sccb.h"
#include "cam_hal.h"
#include "esp_camera.h"
// #include "camera_common.h"
#include "xclk.h"
#if CONFIG_OV2640_SUPPORT
#include "ov2640.h"
#endif
#if CONFIG_OV7725_SUPPORT
#include "ov7725.h"
#endif
#if CONFIG_OV3660_SUPPORT
#include "ov3660.h"
#endif
#if CONFIG_OV5640_SUPPORT
#include "ov5640.h"
#endif
#if CONFIG_NT99141_SUPPORT
#include "nt99141.h"
#endif
#if CONFIG_OV7670_SUPPORT
#include "ov7670.h"
#endif
#if defined(ARDUINO_ARCH_ESP32) && defined(CONFIG_ARDUHAL_ESP_LOG)
#include "esp32-hal-log.h"
#define TAG ""
#else
#include "esp_log.h"
static const char *TAG = "camera";
#endif
typedef struct {
sensor_t sensor;
camera_fb_t fb;
} camera_state_t;
static const char* CAMERA_SENSOR_NVS_KEY = "sensor";
static const char* CAMERA_PIXFORMAT_NVS_KEY = "pixformat";
static camera_state_t *s_state = NULL;
#if CONFIG_IDF_TARGET_ESP32S3 // LCD_CAM module of ESP32-S3 will generate xclk
#define CAMERA_ENABLE_OUT_CLOCK(v)
#define CAMERA_DISABLE_OUT_CLOCK()
#else
#define CAMERA_ENABLE_OUT_CLOCK(v) camera_enable_out_clock((v))
#define CAMERA_DISABLE_OUT_CLOCK() camera_disable_out_clock()
#endif
static esp_err_t camera_probe(const camera_config_t *config, camera_model_t *out_camera_model)
{
*out_camera_model = CAMERA_NONE;
if (s_state != NULL) {
return ESP_ERR_INVALID_STATE;
}
s_state = (camera_state_t *) calloc(sizeof(camera_state_t), 1);
if (!s_state) {
return ESP_ERR_NO_MEM;
}
if (config->pin_xclk >= 0) {
ESP_LOGD(TAG, "Enabling XCLK output");
CAMERA_ENABLE_OUT_CLOCK(config);
}
if (config->pin_sscb_sda != -1) {
ESP_LOGD(TAG, "Initializing SSCB");
SCCB_Init(config->pin_sscb_sda, config->pin_sscb_scl);
}
if (config->pin_pwdn >= 0) {
ESP_LOGD(TAG, "Resetting camera by power down line");
gpio_config_t conf = { 0 };
conf.pin_bit_mask = 1LL << config->pin_pwdn;
conf.mode = GPIO_MODE_OUTPUT;
gpio_config(&conf);
// carefull, logic is inverted compared to reset pin
gpio_set_level(config->pin_pwdn, 1);
vTaskDelay(10 / portTICK_PERIOD_MS);
gpio_set_level(config->pin_pwdn, 0);
vTaskDelay(10 / portTICK_PERIOD_MS);
}
if (config->pin_reset >= 0) {
ESP_LOGD(TAG, "Resetting camera");
gpio_config_t conf = { 0 };
conf.pin_bit_mask = 1LL << config->pin_reset;
conf.mode = GPIO_MODE_OUTPUT;
gpio_config(&conf);
gpio_set_level(config->pin_reset, 0);
vTaskDelay(10 / portTICK_PERIOD_MS);
gpio_set_level(config->pin_reset, 1);
vTaskDelay(10 / portTICK_PERIOD_MS);
}
ESP_LOGD(TAG, "Searching for camera address");
vTaskDelay(10 / portTICK_PERIOD_MS);
uint8_t slv_addr = SCCB_Probe();
if (slv_addr == 0) {
CAMERA_DISABLE_OUT_CLOCK();
return ESP_ERR_NOT_FOUND;
}
ESP_LOGI(TAG, "Detected camera at address=0x%02x", slv_addr);
s_state->sensor.slv_addr = slv_addr;
s_state->sensor.xclk_freq_hz = config->xclk_freq_hz;
/**
* Read sensor ID
*/
sensor_id_t *id = &s_state->sensor.id;
if (slv_addr == OV2640_SCCB_ADDR || slv_addr == OV7725_SCCB_ADDR) {
SCCB_Write(slv_addr, 0xFF, 0x01);//bank sensor
id->PID = SCCB_Read(slv_addr, REG_PID);
id->VER = SCCB_Read(slv_addr, REG_VER);
id->MIDL = SCCB_Read(slv_addr, REG_MIDL);
id->MIDH = SCCB_Read(slv_addr, REG_MIDH);
} else if (slv_addr == OV5640_SCCB_ADDR || slv_addr == OV3660_SCCB_ADDR) {
id->PID = SCCB_Read16(slv_addr, REG16_CHIDH);
id->VER = SCCB_Read16(slv_addr, REG16_CHIDL);
} else if (slv_addr == NT99141_SCCB_ADDR) {
SCCB_Write16(slv_addr, 0x3008, 0x01);//bank sensor
id->PID = SCCB_Read16(slv_addr, 0x3000);
id->VER = SCCB_Read16(slv_addr, 0x3001);
if (config->xclk_freq_hz > 10000000) {
ESP_LOGE(TAG, "NT99141: only XCLK under 10MHz is supported, and XCLK is now set to 10M");
s_state->sensor.xclk_freq_hz = 10000000;
}
}
vTaskDelay(10 / portTICK_PERIOD_MS);
ESP_LOGI(TAG, "Camera PID=0x%02x VER=0x%02x MIDL=0x%02x MIDH=0x%02x",
id->PID, id->VER, id->MIDH, id->MIDL);
/**
* Initialize sensor according to sensor ID
*/
switch (id->PID) {
#if CONFIG_OV2640_SUPPORT
case OV2640_PID:
*out_camera_model = CAMERA_OV2640;
ov2640_init(&s_state->sensor);
break;
#endif
#if CONFIG_OV7725_SUPPORT
case OV7725_PID:
*out_camera_model = CAMERA_OV7725;
ov7725_init(&s_state->sensor);
break;
#endif
#if CONFIG_OV3660_SUPPORT
case OV3660_PID:
*out_camera_model = CAMERA_OV3660;
ov3660_init(&s_state->sensor);
break;
#endif
#if CONFIG_OV5640_SUPPORT
case OV5640_PID:
*out_camera_model = CAMERA_OV5640;
ov5640_init(&s_state->sensor);
break;
#endif
#if CONFIG_OV7670_SUPPORT
case OV7670_PID:
*out_camera_model = CAMERA_OV7670;
ov7670_init(&s_state->sensor);
break;
#endif
#if CONFIG_NT99141_SUPPORT
case NT99141_PID:
*out_camera_model = CAMERA_NT99141;
NT99141_init(&s_state->sensor);
break;
#endif
default:
id->PID = 0;
CAMERA_DISABLE_OUT_CLOCK();
ESP_LOGE(TAG, "Detected camera not supported.");
return ESP_ERR_NOT_SUPPORTED;
}
ESP_LOGD(TAG, "Doing SW reset of sensor");
s_state->sensor.reset(&s_state->sensor);
return ESP_OK;
}
esp_err_t esp_camera_init(const camera_config_t *config)
{
esp_err_t err;
err = cam_init(config);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Camera init failed with error 0x%x", err);
return err;
}
camera_model_t camera_model = CAMERA_NONE;
err = camera_probe(config, &camera_model);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Camera probe failed with error 0x%x(%s)", err, esp_err_to_name(err));
goto fail;
}
if (camera_model == CAMERA_OV7725) {
ESP_LOGI(TAG, "Detected OV7725 camera");
} else if (camera_model == CAMERA_OV2640) {
ESP_LOGI(TAG, "Detected OV2640 camera");
} else if (camera_model == CAMERA_OV3660) {
ESP_LOGI(TAG, "Detected OV3660 camera");
} else if (camera_model == CAMERA_OV5640) {
ESP_LOGI(TAG, "Detected OV5640 camera");
} else if (camera_model == CAMERA_OV7670) {
ESP_LOGI(TAG, "Detected OV7670 camera");
} else if (camera_model == CAMERA_NT99141) {
ESP_LOGI(TAG, "Detected NT99141 camera");
} else {
ESP_LOGI(TAG, "Camera not supported");
err = ESP_ERR_CAMERA_NOT_SUPPORTED;
goto fail;
}
framesize_t frame_size = (framesize_t) config->frame_size;
pixformat_t pix_format = (pixformat_t) config->pixel_format;
if (frame_size > camera_sensor[camera_model].max_size) {
frame_size = camera_sensor[camera_model].max_size;
}
err = cam_config(config, frame_size, s_state->sensor.id.PID);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Camera config failed with error 0x%x", err);
goto fail;
}
s_state->sensor.status.framesize = frame_size;
s_state->sensor.pixformat = pix_format;
// ESP_LOGD(TAG, "Setting frame size to %dx%d", s_state->width, s_state->height);
if (s_state->sensor.set_framesize(&s_state->sensor, frame_size) != 0) {
ESP_LOGE(TAG, "Failed to set frame size");
err = ESP_ERR_CAMERA_FAILED_TO_SET_FRAME_SIZE;
goto fail;
}
s_state->sensor.set_pixformat(&s_state->sensor, pix_format);
if (s_state->sensor.id.PID == OV2640_PID) {
s_state->sensor.set_gainceiling(&s_state->sensor, GAINCEILING_2X);
s_state->sensor.set_bpc(&s_state->sensor, false);
s_state->sensor.set_wpc(&s_state->sensor, true);
s_state->sensor.set_lenc(&s_state->sensor, true);
}
if (pix_format == PIXFORMAT_JPEG) {
(*s_state->sensor.set_quality)(&s_state->sensor, config->jpeg_quality);
}
s_state->sensor.init_status(&s_state->sensor);
cam_start();
return ESP_OK;
fail:
CAMERA_DISABLE_OUT_CLOCK();
return err;
}
esp_err_t esp_camera_deinit()
{
esp_err_t ret = cam_deinit();
if (s_state) {
SCCB_Deinit();
free(s_state);
s_state = NULL;
}
return ret;
}
#define FB_GET_TIMEOUT (4000 / portTICK_PERIOD_MS)
camera_fb_t *esp_camera_fb_get()
{
if (s_state == NULL) {
return NULL;
}
camera_fb_t *fb = cam_take(FB_GET_TIMEOUT);
//set the frame properties
if (fb) {
fb->width = resolution[s_state->sensor.status.framesize].width;
fb->height = resolution[s_state->sensor.status.framesize].height;
fb->format = s_state->sensor.pixformat;
}
return fb;
}
void esp_camera_fb_return(camera_fb_t *fb)
{
if (s_state == NULL) {
return;
}
cam_give(fb);
}
sensor_t *esp_camera_sensor_get()
{
if (s_state == NULL) {
return NULL;
}
return &s_state->sensor;
}
esp_err_t esp_camera_save_to_nvs(const char *key)
{
#if ESP_IDF_VERSION_MAJOR > 3
nvs_handle_t handle;
#else
nvs_handle handle;
#endif
esp_err_t ret = nvs_open(key,NVS_READWRITE,&handle);
if (ret == ESP_OK) {
sensor_t *s = esp_camera_sensor_get();
if (s != NULL) {
ret = nvs_set_blob(handle,CAMERA_SENSOR_NVS_KEY,&s->status,sizeof(camera_status_t));
if (ret == ESP_OK) {
uint8_t pf = s->pixformat;
ret = nvs_set_u8(handle,CAMERA_PIXFORMAT_NVS_KEY,pf);
}
return ret;
} else {
return ESP_ERR_CAMERA_NOT_DETECTED;
}
nvs_close(handle);
return ret;
} else {
return ret;
}
}
esp_err_t esp_camera_load_from_nvs(const char *key)
{
#if ESP_IDF_VERSION_MAJOR > 3
nvs_handle_t handle;
#else
nvs_handle handle;
#endif
uint8_t pf;
esp_err_t ret = nvs_open(key,NVS_READWRITE,&handle);
if (ret == ESP_OK) {
sensor_t *s = esp_camera_sensor_get();
camera_status_t st;
if (s != NULL) {
size_t size = sizeof(camera_status_t);
ret = nvs_get_blob(handle,CAMERA_SENSOR_NVS_KEY,&st,&size);
if (ret == ESP_OK) {
s->set_ae_level(s,st.ae_level);
s->set_aec2(s,st.aec2);
s->set_aec_value(s,st.aec_value);
s->set_agc_gain(s,st.agc_gain);
s->set_awb_gain(s,st.awb_gain);
s->set_bpc(s,st.bpc);
s->set_brightness(s,st.brightness);
s->set_colorbar(s,st.colorbar);
s->set_contrast(s,st.contrast);
s->set_dcw(s,st.dcw);
s->set_denoise(s,st.denoise);
s->set_exposure_ctrl(s,st.aec);
s->set_framesize(s,st.framesize);
s->set_gain_ctrl(s,st.agc);
s->set_gainceiling(s,st.gainceiling);
s->set_hmirror(s,st.hmirror);
s->set_lenc(s,st.lenc);
s->set_quality(s,st.quality);
s->set_raw_gma(s,st.raw_gma);
s->set_saturation(s,st.saturation);
s->set_sharpness(s,st.sharpness);
s->set_special_effect(s,st.special_effect);
s->set_vflip(s,st.vflip);
s->set_wb_mode(s,st.wb_mode);
s->set_whitebal(s,st.awb);
s->set_wpc(s,st.wpc);
}
ret = nvs_get_u8(handle,CAMERA_PIXFORMAT_NVS_KEY,&pf);
if (ret == ESP_OK) {
s->set_pixformat(s,pf);
}
} else {
return ESP_ERR_CAMERA_NOT_DETECTED;
}
nvs_close(handle);
return ret;
} else {
ESP_LOGW(TAG,"Error (%d) opening nvs key \"%s\"",ret,key);
return ret;
}
}

@ -38,7 +38,8 @@
.pixel_format = PIXFORMAT_JPEG,
.frame_size = FRAMESIZE_SVGA,
.jpeg_quality = 10,
.fb_count = 2
.fb_count = 2,
.grab_mode = CAMERA_GRAB_WHEN_EMPTY
};
esp_err_t camera_example_init(){
@ -74,6 +75,14 @@
extern "C" {
#endif
/**
* @brief Configuration structure for camera initialization
*/
typedef enum {
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 */
} camera_grab_mode_t;
/**
* @brief Configuration structure for camera initialization
*/
@ -95,7 +104,7 @@ typedef struct {
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) */
int xclk_freq_hz; /*!< Frequency of XCLK signal, in Hz. EXPERIMENTAL: Set to 16MHz on ESP32-S2 or ESP32-S3 to enable EDMA mode */
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 */
@ -105,6 +114,7 @@ typedef struct {
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_grab_mode_t grab_mode; /*!< When buffers should be filled */
} camera_config_t;
/**

@ -17,7 +17,11 @@
#if ESP_IDF_VERSION_MAJOR >= 4 // IDF 4+
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
#include "esp32/rom/tjpgd.h"
#else
#elif CONFIG_IDF_TARGET_ESP32S2
#include "tjpgd.h"
#elif CONFIG_IDF_TARGET_ESP32S3
#include "esp32s3/rom/tjpgd.h"
#else
#error Target CONFIG_IDF_TARGET is not supported
#endif
#else // ESP32 Before IDF 4.0

@ -22,6 +22,7 @@ extern "C" {
#include <stdint.h>
#include <stdbool.h>
#include "esp_camera.h"
#include "esp_jpg_decode.h"
typedef size_t (* jpg_out_cb)(void * arg, size_t index, const void* data, size_t len);
@ -120,6 +121,8 @@ bool frame2bmp(camera_fb_t * fb, uint8_t ** out, size_t * out_len);
*/
bool fmt2rgb888(const uint8_t *src_buf, size_t src_len, pixformat_t format, uint8_t * rgb_buf);
bool jpg2rgb565(const uint8_t *src, size_t src_len, uint8_t * out, jpg_scale_t scale);
#ifdef __cplusplus
}
#endif

@ -0,0 +1,26 @@
{
"name": "esp32-camera",
"version": "1.0.0",
"keywords": "esp32, camera, espressif, esp32-cam",
"description": "ESP32 compatible driver for OV2640, OV3660, OV5640, OV7670 and OV7725 image sensors.",
"repository": {
"type": "git",
"url": "https://github.com/espressif/esp32-camera"
},
"frameworks": "espidf",
"platforms": "*",
"build": {
"flags": [
"-Idriver/include",
"-Iconversions/include",
"-Idriver/private_include",
"-Iconversions/private_include",
"-Isensors/private_include",
"-Itarget/private_include",
"-fno-rtti"
],
"includeDir": ".",
"srcDir": ".",
"srcFilter": ["-<*>", "+<driver>", "+<conversions>", "+<sensors>"]
}
}

@ -0,0 +1,515 @@
// Copyright 2010-2020 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.
#include <stdio.h>
#include <string.h>
#include "soc/i2s_struct.h"
#include "esp_idf_version.h"
#if ESP_IDF_VERSION_MAJOR >= 4
#include "hal/gpio_ll.h"
#else
#include "rom/ets_sys.h"
#include "soc/gpio_periph.h"
#define esp_rom_delay_us ets_delay_us
static inline int gpio_ll_get_level(gpio_dev_t *hw, int gpio_num)
{
if (gpio_num < 32) {
return (hw->in >> gpio_num) & 0x1;
} else {
return (hw->in1.data >> (gpio_num - 32)) & 0x1;
}
}
#endif
#include "ll_cam.h"
#include "xclk.h"
#include "cam_hal.h"
static const char *TAG = "esp32 ll_cam";
#define I2S_ISR_ENABLE(i) {I2S0.int_clr.i = 1;I2S0.int_ena.i = 1;}
#define I2S_ISR_DISABLE(i) {I2S0.int_ena.i = 0;I2S0.int_clr.i = 1;}
typedef union {
struct {
uint32_t sample2:8;
uint32_t unused2:8;
uint32_t sample1:8;
uint32_t unused1:8;
};
uint32_t val;
} dma_elem_t;
typedef enum {
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 s2, 00 s2 00 s3, 00 s3 00 s4, ...
*/
SM_0A0B_0B0C = 0,
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 s2, 00 s3 00 s4, ...
*/
SM_0A0B_0C0D = 1,
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 00, 00 s2 00 00, 00 s3 00 00, ...
*/
SM_0A00_0B00 = 3,
} i2s_sampling_mode_t;
typedef size_t (*dma_filter_t)(uint8_t* dst, const uint8_t* src, size_t len);
static i2s_sampling_mode_t sampling_mode = SM_0A00_0B00;
static size_t ll_cam_bytes_per_sample(i2s_sampling_mode_t mode)
{
switch(mode) {
case SM_0A00_0B00:
return 4;
case SM_0A0B_0B0C:
return 4;
case SM_0A0B_0C0D:
return 2;
default:
assert(0 && "invalid sampling mode");
return 0;
}
}
static size_t IRAM_ATTR ll_cam_dma_filter_jpeg(uint8_t* dst, const uint8_t* src, size_t len)
{
const dma_elem_t* dma_el = (const dma_elem_t*)src;
size_t elements = len / sizeof(dma_elem_t);
size_t end = elements / 4;
// manually unrolling 4 iterations of the loop here
for (size_t i = 0; i < end; ++i) {
dst[0] = dma_el[0].sample1;
dst[1] = dma_el[1].sample1;
dst[2] = dma_el[2].sample1;
dst[3] = dma_el[3].sample1;
dma_el += 4;
dst += 4;
}
return elements;
}
static size_t IRAM_ATTR ll_cam_dma_filter_grayscale(uint8_t* dst, const uint8_t* src, size_t len)
{
const dma_elem_t* dma_el = (const dma_elem_t*)src;
size_t elements = len / sizeof(dma_elem_t);
size_t end = elements / 4;
for (size_t i = 0; i < end; ++i) {
// manually unrolling 4 iterations of the loop here
dst[0] = dma_el[0].sample1;
dst[1] = dma_el[1].sample1;
dst[2] = dma_el[2].sample1;
dst[3] = dma_el[3].sample1;
dma_el += 4;
dst += 4;
}
return elements;
}
static size_t IRAM_ATTR ll_cam_dma_filter_grayscale_highspeed(uint8_t* dst, const uint8_t* src, size_t len)
{
const dma_elem_t* dma_el = (const dma_elem_t*)src;
size_t elements = len / sizeof(dma_elem_t);
size_t end = elements / 8;
for (size_t i = 0; i < end; ++i) {
// manually unrolling 4 iterations of the loop here
dst[0] = dma_el[0].sample1;
dst[1] = dma_el[2].sample1;
dst[2] = dma_el[4].sample1;
dst[3] = dma_el[6].sample1;
dma_el += 8;
dst += 4;
}
// the final sample of a line in SM_0A0B_0B0C sampling mode needs special handling
if ((elements & 0x7) != 0) {
dst[0] = dma_el[0].sample1;
dst[1] = dma_el[2].sample1;
elements += 1;
}
return elements / 2;
}
static size_t IRAM_ATTR ll_cam_dma_filter_yuyv(uint8_t* dst, const uint8_t* src, size_t len)
{
const dma_elem_t* dma_el = (const dma_elem_t*)src;
size_t elements = len / sizeof(dma_elem_t);
size_t end = elements / 4;
for (size_t i = 0; i < end; ++i) {
dst[0] = dma_el[0].sample1;//y0
dst[1] = dma_el[0].sample2;//u
dst[2] = dma_el[1].sample1;//y1
dst[3] = dma_el[1].sample2;//v
dst[4] = dma_el[2].sample1;//y0
dst[5] = dma_el[2].sample2;//u
dst[6] = dma_el[3].sample1;//y1
dst[7] = dma_el[3].sample2;//v
dma_el += 4;
dst += 8;
}
return elements * 2;
}
static size_t IRAM_ATTR ll_cam_dma_filter_yuyv_highspeed(uint8_t* dst, const uint8_t* src, size_t len)
{
const dma_elem_t* dma_el = (const dma_elem_t*)src;
size_t elements = len / sizeof(dma_elem_t);
size_t end = elements / 8;
for (size_t i = 0; i < end; ++i) {
dst[0] = dma_el[0].sample1;//y0
dst[1] = dma_el[1].sample1;//u
dst[2] = dma_el[2].sample1;//y1
dst[3] = dma_el[3].sample1;//v
dst[4] = dma_el[4].sample1;//y0
dst[5] = dma_el[5].sample1;//u
dst[6] = dma_el[6].sample1;//y1
dst[7] = dma_el[7].sample1;//v
dma_el += 8;
dst += 8;
}
if ((elements & 0x7) != 0) {
dst[0] = dma_el[0].sample1;//y0
dst[1] = dma_el[1].sample1;//u
dst[2] = dma_el[2].sample1;//y1
dst[3] = dma_el[2].sample2;//v
elements += 4;
}
return elements;
}
static void IRAM_ATTR ll_cam_vsync_isr(void *arg)
{
//DBG_PIN_SET(1);
cam_obj_t *cam = (cam_obj_t *)arg;
BaseType_t HPTaskAwoken = pdFALSE;
// filter
esp_rom_delay_us(1);
if (gpio_ll_get_level(&GPIO, cam->vsync_pin) == !cam->vsync_invert) {
ll_cam_send_event(cam, CAM_VSYNC_EVENT, &HPTaskAwoken);
if (HPTaskAwoken == pdTRUE) {
portYIELD_FROM_ISR();
}
}
//DBG_PIN_SET(0);
}
static void IRAM_ATTR ll_cam_dma_isr(void *arg)
{
//DBG_PIN_SET(1);
cam_obj_t *cam = (cam_obj_t *)arg;
BaseType_t HPTaskAwoken = pdFALSE;
typeof(I2S0.int_st) status = I2S0.int_st;
if (status.val == 0) {
return;
}
I2S0.int_clr.val = status.val;
if (status.in_suc_eof) {
ll_cam_send_event(cam, CAM_IN_SUC_EOF_EVENT, &HPTaskAwoken);
}
if (HPTaskAwoken == pdTRUE) {
portYIELD_FROM_ISR();
}
//DBG_PIN_SET(0);
}
bool ll_cam_stop(cam_obj_t *cam)
{
I2S0.conf.rx_start = 0;
I2S_ISR_DISABLE(in_suc_eof);
I2S0.in_link.stop = 1;
return true;
}
bool ll_cam_start(cam_obj_t *cam, int frame_pos)
{
I2S0.conf.rx_start = 0;
I2S_ISR_ENABLE(in_suc_eof);
I2S0.conf.rx_reset = 1;
I2S0.conf.rx_reset = 0;
I2S0.conf.rx_fifo_reset = 1;
I2S0.conf.rx_fifo_reset = 0;
I2S0.lc_conf.in_rst = 1;
I2S0.lc_conf.in_rst = 0;
I2S0.lc_conf.ahbm_fifo_rst = 1;
I2S0.lc_conf.ahbm_fifo_rst = 0;
I2S0.lc_conf.ahbm_rst = 1;
I2S0.lc_conf.ahbm_rst = 0;
I2S0.rx_eof_num = cam->dma_half_buffer_size / sizeof(dma_elem_t);
I2S0.in_link.addr = ((uint32_t)&cam->dma[0]) & 0xfffff;
I2S0.in_link.start = 1;
I2S0.conf.rx_start = 1;
return true;
}
esp_err_t ll_cam_config(cam_obj_t *cam, const camera_config_t *config)
{
// Enable and configure I2S peripheral
periph_module_enable(PERIPH_I2S0_MODULE);
I2S0.conf.rx_reset = 1;
I2S0.conf.rx_reset = 0;
I2S0.conf.rx_fifo_reset = 1;
I2S0.conf.rx_fifo_reset = 0;
I2S0.lc_conf.in_rst = 1;
I2S0.lc_conf.in_rst = 0;
I2S0.lc_conf.ahbm_fifo_rst = 1;
I2S0.lc_conf.ahbm_fifo_rst = 0;
I2S0.lc_conf.ahbm_rst = 1;
I2S0.lc_conf.ahbm_rst = 0;
I2S0.conf.rx_slave_mod = 1;
I2S0.conf.rx_right_first = 0;
I2S0.conf.rx_msb_right = 0;
I2S0.conf.rx_msb_shift = 0;
I2S0.conf.rx_mono = 0;
I2S0.conf.rx_short_sync = 0;
I2S0.conf2.lcd_en = 1;
I2S0.conf2.camera_en = 1;
// Configure clock divider
I2S0.clkm_conf.clkm_div_a = 0;
I2S0.clkm_conf.clkm_div_b = 0;
I2S0.clkm_conf.clkm_div_num = 2;
I2S0.fifo_conf.dscr_en = 1;
I2S0.fifo_conf.rx_fifo_mod = sampling_mode;
I2S0.fifo_conf.rx_fifo_mod_force_en = 1;
I2S0.conf_chan.rx_chan_mod = 1;
I2S0.sample_rate_conf.rx_bits_mod = 0;
I2S0.timing.val = 0;
I2S0.timing.rx_dsync_sw = 1;
return ESP_OK;
}
void ll_cam_vsync_intr_enable(cam_obj_t *cam, bool en)
{
if (en) {
gpio_intr_enable(cam->vsync_pin);
} else {
gpio_intr_disable(cam->vsync_pin);
}
}
esp_err_t ll_cam_set_pin(cam_obj_t *cam, const camera_config_t *config)
{
gpio_config_t io_conf = {0};
io_conf.intr_type = cam->vsync_invert ? GPIO_PIN_INTR_NEGEDGE : GPIO_PIN_INTR_POSEDGE;
io_conf.pin_bit_mask = 1ULL << config->pin_vsync;
io_conf.mode = GPIO_MODE_INPUT;
io_conf.pull_up_en = 1;
io_conf.pull_down_en = 0;
gpio_config(&io_conf);
gpio_install_isr_service(ESP_INTR_FLAG_LOWMED | ESP_INTR_FLAG_IRAM);
gpio_isr_handler_add(config->pin_vsync, ll_cam_vsync_isr, cam);
gpio_intr_disable(config->pin_vsync);
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[config->pin_pclk], PIN_FUNC_GPIO);
gpio_set_direction(config->pin_pclk, GPIO_MODE_INPUT);
gpio_set_pull_mode(config->pin_pclk, GPIO_FLOATING);
gpio_matrix_in(config->pin_pclk, I2S0I_WS_IN_IDX, false);
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[config->pin_vsync], PIN_FUNC_GPIO);
gpio_set_direction(config->pin_vsync, GPIO_MODE_INPUT);
gpio_set_pull_mode(config->pin_vsync, GPIO_FLOATING);
gpio_matrix_in(config->pin_vsync, I2S0I_V_SYNC_IDX, false);
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[config->pin_href], PIN_FUNC_GPIO);
gpio_set_direction(config->pin_href, GPIO_MODE_INPUT);
gpio_set_pull_mode(config->pin_href, GPIO_FLOATING);
gpio_matrix_in(config->pin_href, I2S0I_H_SYNC_IDX, false);
int data_pins[8] = {
config->pin_d0, config->pin_d1, config->pin_d2, config->pin_d3, config->pin_d4, config->pin_d5, config->pin_d6, config->pin_d7,
};
for (int i = 0; i < 8; i++) {
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[data_pins[i]], PIN_FUNC_GPIO);
gpio_set_direction(data_pins[i], GPIO_MODE_INPUT);
gpio_set_pull_mode(data_pins[i], GPIO_FLOATING);
gpio_matrix_in(data_pins[i], I2S0I_DATA_IN0_IDX + i, false);
}
gpio_matrix_in(0x38, I2S0I_H_ENABLE_IDX, false);
return ESP_OK;
}
esp_err_t ll_cam_init_isr(cam_obj_t *cam)
{
return esp_intr_alloc(ETS_I2S0_INTR_SOURCE, ESP_INTR_FLAG_LOWMED | ESP_INTR_FLAG_IRAM, ll_cam_dma_isr, cam, &cam->cam_intr_handle);
}
void ll_cam_do_vsync(cam_obj_t *cam)
{
}
uint8_t ll_cam_get_dma_align(cam_obj_t *cam)
{
return 0;
}
static bool ll_cam_calc_rgb_dma(cam_obj_t *cam){
size_t dma_half_buffer_max = 16 * 1024 / cam->dma_bytes_per_item;
size_t dma_buffer_max = 2 * dma_half_buffer_max;
size_t node_max = LCD_CAM_DMA_NODE_BUFFER_MAX_SIZE / cam->dma_bytes_per_item;
size_t line_width = cam->width * cam->in_bytes_per_pixel;
size_t image_size = cam->height * line_width;
if (image_size > (2 * 1024 * 1024) || (line_width > dma_half_buffer_max)) {
ESP_LOGE(TAG, "Resolution too high");
return 0;
}
size_t node_size = node_max;
size_t nodes_per_line = 1;
size_t lines_per_node = 1;
size_t lines_per_half_buffer = 1;
size_t dma_half_buffer_min = node_max;
size_t dma_half_buffer = dma_half_buffer_max;
size_t dma_buffer_size = dma_buffer_max;
// Calculate DMA Node Size so that it's divisable by or divisor of the line width
if(line_width >= node_max){
// One or more nodes will be requied for one line
for(size_t i = node_max; i > 0; i=i-1){
if ((line_width % i) == 0) {
node_size = i;
nodes_per_line = line_width / node_size;
break;
}
}
} else {
// One or more lines can fit into one node
for(size_t i = node_max; i > 0; i=i-1){
if ((i % line_width) == 0) {
node_size = i;
lines_per_node = node_size / line_width;
while((cam->height % lines_per_node) != 0){
lines_per_node = lines_per_node - 1;
node_size = lines_per_node * line_width;
}
break;
}
}
}
// Calculate minimum EOF size = max(mode_size, line_size)
dma_half_buffer_min = node_size * nodes_per_line;
// Calculate max EOF size divisable by node size
dma_half_buffer = (dma_half_buffer_max / dma_half_buffer_min) * dma_half_buffer_min;
// Adjust EOF size so that height will be divisable by the number of lines in each EOF
lines_per_half_buffer = dma_half_buffer / line_width;
while((cam->height % lines_per_half_buffer) != 0){
dma_half_buffer = dma_half_buffer - dma_half_buffer_min;
lines_per_half_buffer = dma_half_buffer / line_width;
}
// Calculate DMA size
dma_buffer_size =(dma_buffer_max / dma_half_buffer) * dma_half_buffer;
ESP_LOGI(TAG, "node_size: %4u, nodes_per_line: %u, lines_per_node: %u, dma_half_buffer_min: %5u, dma_half_buffer: %5u, lines_per_half_buffer: %2u, dma_buffer_size: %5u, image_size: %u",
node_size * cam->dma_bytes_per_item, nodes_per_line, lines_per_node, dma_half_buffer_min * cam->dma_bytes_per_item, dma_half_buffer * cam->dma_bytes_per_item, lines_per_half_buffer, dma_buffer_size * cam->dma_bytes_per_item, image_size);
cam->dma_buffer_size = dma_buffer_size * cam->dma_bytes_per_item;
cam->dma_half_buffer_size = dma_half_buffer * cam->dma_bytes_per_item;
cam->dma_node_buffer_size = node_size * cam->dma_bytes_per_item;
cam->dma_half_buffer_cnt = cam->dma_buffer_size / cam->dma_half_buffer_size;
return 1;
}
bool ll_cam_dma_sizes(cam_obj_t *cam)
{
cam->dma_bytes_per_item = ll_cam_bytes_per_sample(sampling_mode);
if (cam->jpeg_mode) {
cam->dma_half_buffer_cnt = 8;
cam->dma_node_buffer_size = 2048;
cam->dma_half_buffer_size = cam->dma_node_buffer_size * 2;
cam->dma_buffer_size = cam->dma_half_buffer_cnt * cam->dma_half_buffer_size;
} else {
return ll_cam_calc_rgb_dma(cam);
}
return 1;
}
static dma_filter_t dma_filter = ll_cam_dma_filter_jpeg;
size_t IRAM_ATTR ll_cam_memcpy(cam_obj_t *cam, uint8_t *out, const uint8_t *in, size_t len)
{
//DBG_PIN_SET(1);
size_t r = dma_filter(out, in, len);
//DBG_PIN_SET(0);
return r;
}
esp_err_t ll_cam_set_sample_mode(cam_obj_t *cam, pixformat_t pix_format, uint32_t xclk_freq_hz, uint8_t sensor_pid)
{
if (pix_format == PIXFORMAT_GRAYSCALE) {
if (sensor_pid == OV3660_PID || sensor_pid == OV5640_PID || sensor_pid == NT99141_PID) {
if (xclk_freq_hz > 10000000) {
sampling_mode = SM_0A00_0B00;
dma_filter = ll_cam_dma_filter_yuyv_highspeed;
} else {
sampling_mode = SM_0A0B_0C0D;
dma_filter = ll_cam_dma_filter_yuyv;
}
cam->in_bytes_per_pixel = 1; // camera sends Y8
} else {
if (xclk_freq_hz > 10000000 && sensor_pid != OV7725_PID) {
sampling_mode = SM_0A00_0B00;
dma_filter = ll_cam_dma_filter_grayscale_highspeed;
} else {
sampling_mode = SM_0A0B_0C0D;
dma_filter = ll_cam_dma_filter_grayscale;
}
cam->in_bytes_per_pixel = 2; // camera sends YU/YV
}
cam->fb_bytes_per_pixel = 1; // frame buffer stores Y8
} else if (pix_format == PIXFORMAT_YUV422 || pix_format == PIXFORMAT_RGB565) {
if (xclk_freq_hz > 10000000 && sensor_pid != OV7725_PID) {
if (sensor_pid == OV7670_PID) {
sampling_mode = SM_0A0B_0B0C;
} else {
sampling_mode = SM_0A00_0B00;
}
dma_filter = ll_cam_dma_filter_yuyv_highspeed;
} else {
sampling_mode = SM_0A0B_0C0D;
dma_filter = ll_cam_dma_filter_yuyv;
}
cam->in_bytes_per_pixel = 2; // camera sends YU/YV
cam->fb_bytes_per_pixel = 2; // frame buffer stores YU/YV/RGB565
} else if (pix_format == PIXFORMAT_JPEG) {
if (sensor_pid != OV2640_PID && sensor_pid != OV3660_PID && sensor_pid != OV5640_PID && sensor_pid != NT99141_PID) {
ESP_LOGE(TAG, "JPEG format is not supported on this sensor");
return ESP_ERR_NOT_SUPPORTED;
}
cam->in_bytes_per_pixel = 1;
cam->fb_bytes_per_pixel = 1;
dma_filter = ll_cam_dma_filter_jpeg;
sampling_mode = SM_0A00_0B00;
} else {
ESP_LOGE(TAG, "Requested format is not supported");
return ESP_ERR_NOT_SUPPORTED;
}
I2S0.fifo_conf.rx_fifo_mod = sampling_mode;
return ESP_OK;
}

@ -0,0 +1,136 @@
// Copyright 2010-2020 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.
#pragma once
#include <stdint.h>
#include "sdkconfig.h"
#if CONFIG_IDF_TARGET_ESP32
#if ESP_IDF_VERSION_MAJOR >= 4
#include "esp32/rom/lldesc.h"
#else
#include "rom/lldesc.h"
#endif
#elif CONFIG_IDF_TARGET_ESP32S2
#include "esp32s2/rom/lldesc.h"
#elif CONFIG_IDF_TARGET_ESP32S3
#include "esp32s3/rom/lldesc.h"
#endif
#include "esp_log.h"
#include "esp_camera.h"
#include "camera_common.h"
#include "freertos/FreeRTOS.h"
#include "freertos/queue.h"
#include "freertos/task.h"
#include "freertos/semphr.h"
#define CAMERA_DBG_PIN_ENABLE 0
#if CAMERA_DBG_PIN_ENABLE
#if CONFIG_IDF_TARGET_ESP32
#define DBG_PIN_NUM 26
#else
#define DBG_PIN_NUM 7
#endif
#include "hal/gpio_ll.h"
#define DBG_PIN_SET(v) gpio_ll_set_level(&GPIO, DBG_PIN_NUM, v)
#else
#define DBG_PIN_SET(v)
#endif
#define CAM_CHECK(a, str, ret) if (!(a)) { \
ESP_LOGE(TAG,"%s(%d): %s", __FUNCTION__, __LINE__, str); \
return (ret); \
}
#define CAM_CHECK_GOTO(a, str, lab) if (!(a)) { \
ESP_LOGE(TAG,"%s(%d): %s", __FUNCTION__, __LINE__, str); \
goto lab; \
}
#define LCD_CAM_DMA_NODE_BUFFER_MAX_SIZE (4092)
typedef enum {
CAM_IN_SUC_EOF_EVENT = 0,
CAM_VSYNC_EVENT
} cam_event_t;
typedef enum {
CAM_STATE_IDLE = 0,
CAM_STATE_READ_BUF = 1,
} cam_state_t;
typedef struct {
camera_fb_t fb;
uint8_t en;
//for RGB/YUV modes
lldesc_t *dma;
size_t fb_offset;
} cam_frame_t;
typedef struct {
uint32_t dma_bytes_per_item;
uint32_t dma_buffer_size;
uint32_t dma_half_buffer_size;
uint32_t dma_half_buffer_cnt;
uint32_t dma_node_buffer_size;
uint32_t dma_node_cnt;
uint32_t frame_copy_cnt;
//for JPEG mode
lldesc_t *dma;
uint8_t *dma_buffer;
cam_frame_t *frames;
QueueHandle_t event_queue;
QueueHandle_t frame_buffer_queue;
TaskHandle_t task_handle;
intr_handle_t cam_intr_handle;
uint8_t dma_num;//ESP32-S3
intr_handle_t dma_intr_handle;//ESP32-S3
uint8_t jpeg_mode;
uint8_t vsync_pin;
uint8_t vsync_invert;
uint32_t frame_cnt;
uint32_t recv_size;
bool swap_data;
bool psram_mode;
//for RGB/YUV modes
uint16_t width;
uint16_t height;
uint8_t in_bytes_per_pixel;
uint8_t fb_bytes_per_pixel;
uint32_t fb_size;
cam_state_t state;
} cam_obj_t;
bool ll_cam_stop(cam_obj_t *cam);
bool ll_cam_start(cam_obj_t *cam, int frame_pos);
esp_err_t ll_cam_config(cam_obj_t *cam, const camera_config_t *config);
void ll_cam_vsync_intr_enable(cam_obj_t *cam, bool en);
esp_err_t ll_cam_set_pin(cam_obj_t *cam, const camera_config_t *config);
esp_err_t ll_cam_init_isr(cam_obj_t *cam);
void ll_cam_do_vsync(cam_obj_t *cam);
uint8_t ll_cam_get_dma_align(cam_obj_t *cam);
bool ll_cam_dma_sizes(cam_obj_t *cam);
size_t ll_cam_memcpy(cam_obj_t *cam, uint8_t *out, const uint8_t *in, size_t len);
esp_err_t ll_cam_set_sample_mode(cam_obj_t *cam, pixformat_t pix_format, uint32_t xclk_freq_hz, uint8_t sensor_pid);
// implemented in cam_hal
void ll_cam_send_event(cam_obj_t *cam, cam_event_t cam_event, BaseType_t * HPTaskAwoken);

@ -144,28 +144,6 @@ static int write_addr_reg(uint8_t slv_addr, const uint16_t reg, uint16_t x_value
#define write_reg_bits(slv_addr, reg, mask, enable) set_reg_bits(slv_addr, reg, 0, mask, enable?mask:0)
static int calc_sysclk(int xclk, bool pll_bypass, int pll_multiplier, int pll_sys_div, int pll_pre_div, bool pll_root_2x, int pll_seld5, bool pclk_manual, int pclk_div)
{
const int pll_pre_div2x_map[] = { 2, 3, 4, 6 };//values are multiplied by two to avoid floats
const int pll_seld52x_map[] = { 2, 2, 4, 5 };
if (!pll_sys_div) {
pll_sys_div = 1;
}
int pll_pre_div2x = pll_pre_div2x_map[pll_pre_div];
int pll_root_div = pll_root_2x ? 2 : 1;
int pll_seld52x = pll_seld52x_map[pll_seld5];
int VCO = (xclk / 1000) * pll_multiplier * pll_root_div * 2 / pll_pre_div2x;
int PLLCLK = pll_bypass ? (xclk) : (VCO * 1000 * 2 / pll_sys_div / pll_seld52x);
int PCLK = PLLCLK / 2 / ((pclk_manual && pclk_div) ? pclk_div : 1);
int SYSCLK = PLLCLK / 4;
ESP_LOGD(TAG, "Calculated VCO: %d Hz, PLLCLK: %d Hz, SYSCLK: %d Hz, PCLK: %d Hz", VCO * 1000, PLLCLK, SYSCLK, PCLK);
return SYSCLK;
}
static int set_pll(sensor_t *sensor, bool bypass, uint8_t multiplier, uint8_t sys_div, uint8_t pre_div, bool root_2x, uint8_t seld5, bool pclk_manual, uint8_t pclk_div)
{
return -1;
@ -309,7 +287,7 @@ static int set_framesize(sensor_t *sensor, framesize_t framesize)
ret = write_regs(sensor->slv_addr, sensor_framesize_VGA);
}
return 0;
return ret;
}
static int set_hmirror(sensor_t *sensor, int enable)
@ -682,7 +660,6 @@ static int set_brightness(sensor_t *sensor, int level)
{
int ret = 0;
uint8_t value = 0;
bool negative = false;
switch (level) {
case 3:
@ -699,17 +676,14 @@ static int set_brightness(sensor_t *sensor, int level)
case -1:
value = 0x78;
negative = true;
break;
case -2:
value = 0x70;
negative = true;
break;
case -3:
value = 0x60;
negative = true;
break;
default: // 0
@ -730,7 +704,6 @@ static int set_contrast(sensor_t *sensor, int level)
{
int ret = 0;
uint8_t value1 = 0, value2 = 0 ;
bool negative = false;
switch (level) {
case 3:

@ -157,26 +157,40 @@ static int set_window(sensor_t *sensor, ov2640_sensor_mode_t mode, int offset_x,
{0, 0}
};
c.pclk_auto = 0;
c.pclk_div = 8;
c.clk_2x = 0;
c.clk_div = 0;
if(sensor->pixformat != PIXFORMAT_JPEG){
c.pclk_auto = 1;
if (sensor->pixformat == PIXFORMAT_JPEG) {
c.clk_2x = 0;
c.clk_div = 0;
c.pclk_auto = 0;
c.pclk_div = 8;
if(mode == OV2640_MODE_UXGA) {
c.pclk_div = 12;
}
// if (sensor->xclk_freq_hz == 16000000) {
// c.pclk_div = c.pclk_div / 2;
// }
} else {
#if CONFIG_IDF_TARGET_ESP32
c.clk_2x = 0;
#else
c.clk_2x = 1;
#endif
c.clk_div = 7;
c.pclk_auto = 1;
c.pclk_div = 8;
if (mode == OV2640_MODE_CIF) {
c.clk_div = 3;
} else if(mode == OV2640_MODE_UXGA) {
c.pclk_div = 12;
}
}
ESP_LOGI(TAG, "Set PLL: clk_2x: %u, clk_div: %u, pclk_auto: %u, pclk_div: %u", c.clk_2x, c.clk_div, c.pclk_auto, c.pclk_div);
if (mode == OV2640_MODE_CIF) {
regs = ov2640_settings_to_cif;
if(sensor->pixformat != PIXFORMAT_JPEG){
c.clk_div = 3;
}
} else if (mode == OV2640_MODE_SVGA) {
regs = ov2640_settings_to_svga;
} else {
regs = ov2640_settings_to_uxga;
c.pclk_div = 12;
}
WRITE_REG_OR_RETURN(BANK_DSP, R_BYPASS, R_BYPASS_DSP_BYPAS);

@ -142,7 +142,7 @@ static int calc_sysclk(int xclk, bool pll_bypass, int pll_multiplier, int pll_sy
int PCLK = PLLCLK / 2 / ((pclk_manual && pclk_div)?pclk_div:1);
int SYSCLK = PLLCLK / 4;
ESP_LOGD(TAG, "Calculated VCO: %d Hz, PLLCLK: %d Hz, SYSCLK: %d Hz, PCLK: %d Hz", VCO*1000, PLLCLK, SYSCLK, PCLK);
ESP_LOGI(TAG, "Calculated VCO: %d Hz, PLLCLK: %d Hz, SYSCLK: %d Hz, PCLK: %d Hz", VCO*1000, PLLCLK, SYSCLK, PCLK);
return SYSCLK;
}
@ -310,13 +310,13 @@ static int set_image_options(sensor_t *sensor)
static int set_framesize(sensor_t *sensor, framesize_t framesize)
{
int ret = 0;
framesize_t old_framesize = sensor->status.framesize;
sensor->status.framesize = framesize;
if(framesize > FRAMESIZE_QXGA){
ESP_LOGE(TAG, "Invalid framesize: %u", framesize);
return -1;
ESP_LOGW(TAG, "Invalid framesize: %u", framesize);
framesize = FRAMESIZE_QXGA;
}
framesize_t old_framesize = sensor->status.framesize;
sensor->status.framesize = framesize;
uint16_t w = resolution[framesize].width;
uint16_t h = resolution[framesize].height;
aspect_ratio_t ratio = resolution[sensor->status.framesize].aspect_ratio;
@ -355,7 +355,7 @@ static int set_framesize(sensor_t *sensor, framesize_t framesize)
}
if (sensor->pixformat == PIXFORMAT_JPEG) {
if (framesize == FRAMESIZE_QXGA) {
if (framesize == FRAMESIZE_QXGA || sensor->xclk_freq_hz == 16000000) {
//40MHz SYSCLK and 10MHz PCLK
ret = set_pll(sensor, false, 24, 1, 3, false, 0, true, 8);
} else {
@ -363,12 +363,16 @@ static int set_framesize(sensor_t *sensor, framesize_t framesize)
ret = set_pll(sensor, false, 30, 1, 3, false, 0, true, 10);
}
} else {
if (framesize > FRAMESIZE_CIF) {
//10MHz SYSCLK and 10MHz PCLK (6.19 FPS)
ret = set_pll(sensor, false, 2, 1, 0, false, 0, true, 2);
//tuned for 16MHz XCLK and 8MHz PCLK
if (framesize > FRAMESIZE_HVGA) {
//8MHz SYSCLK and 8MHz PCLK (4.44 FPS)
ret = set_pll(sensor, false, 4, 1, 0, false, 2, true, 2);
} else if (framesize >= FRAMESIZE_QVGA) {
//16MHz SYSCLK and 8MHz PCLK (10.25 FPS)
ret = set_pll(sensor, false, 8, 1, 0, false, 2, true, 4);
} else {
//25MHz SYSCLK and 10MHz PCLK (15.45 FPS)
ret = set_pll(sensor, false, 5, 1, 0, false, 0, true, 5);
//32MHz SYSCLK and 8MHz PCLK (17.77 FPS)
ret = set_pll(sensor, false, 8, 1, 0, false, 0, true, 8);
}
}

@ -196,7 +196,7 @@ static int calc_sysclk(int xclk, bool pll_bypass, int pll_multiplier, int pll_sy
unsigned int SYSCLK = PLL_CLK / 4;
ESP_LOGD(TAG, "Calculated XVCLK: %d Hz, REFIN: %u Hz, VCO: %u Hz, PLL_CLK: %u Hz, SYSCLK: %u Hz, PCLK: %u Hz", xclk, REFIN, VCO, PLL_CLK, SYSCLK, PCLK);
ESP_LOGI(TAG, "Calculated XVCLK: %d Hz, REFIN: %u Hz, VCO: %u Hz, PLL_CLK: %u Hz, SYSCLK: %u Hz, PCLK: %u Hz", xclk, REFIN, VCO, PLL_CLK, SYSCLK, PCLK);
return SYSCLK;
}
@ -209,6 +209,7 @@ static int set_pll(sensor_t *sensor, bool bypass, uint8_t multiplier, uint8_t sy
if(multiplier > 127){
multiplier &= 0xFE;//only even integers above 127
}
ESP_LOGI(TAG, "Set PLL: bypass: %u, multiplier: %u, sys_div: %u, pre_div: %u, root_2x: %u, pclk_root_div: %u, pclk_manual: %u, pclk_div: %u", bypass, multiplier, sys_div, pre_div, root_2x, pclk_root_div, pclk_manual, pclk_div);
calc_sysclk(sensor->xclk_freq_hz, bypass, multiplier, sys_div, pre_div, root_2x, pclk_root_div, pclk_manual, pclk_div);
@ -432,14 +433,22 @@ static int set_framesize(sensor_t *sensor, framesize_t framesize)
if (sensor->pixformat == PIXFORMAT_JPEG) {
//10MHz PCLK
uint8_t sys_mul = 200;
if(framesize < FRAMESIZE_QVGA){
if(framesize < FRAMESIZE_QVGA || sensor->xclk_freq_hz == 16000000){
sys_mul = 160;
} else if(framesize < FRAMESIZE_XGA){
sys_mul = 180;
}
ret = set_pll(sensor, false, sys_mul, 4, 2, false, 2, true, 4);
//Set PLL: bypass: 0, multiplier: sys_mul, sys_div: 4, pre_div: 2, root_2x: 0, pclk_root_div: 2, pclk_manual: 1, pclk_div: 4
} else {
ret = set_pll(sensor, false, 10, 1, 1, false, 1, true, 4);
//ret = set_pll(sensor, false, 8, 1, 1, false, 1, true, 4);
if (framesize > FRAMESIZE_HVGA) {
ret = set_pll(sensor, false, 10, 1, 2, false, 1, true, 2);
} else if (framesize >= FRAMESIZE_QVGA) {
ret = set_pll(sensor, false, 8, 1, 1, false, 1, true, 4);
} else {
ret = set_pll(sensor, false, 20, 1, 1, false, 1, true, 8);
}
}
if (ret == 0) {

@ -11,6 +11,7 @@
#include <freertos/FreeRTOS.h>
#include <freertos/task.h>
#include "sccb.h"
#include "sensor.h"
#include <stdio.h>
#include "sdkconfig.h"
#if defined(ARDUINO_ARCH_ESP32) && defined(CONFIG_ARDUHAL_ESP_LOG)
@ -36,12 +37,10 @@ const int SCCB_I2C_PORT = 1;
#else
const int SCCB_I2C_PORT = 0;
#endif
static uint8_t ESP_SLAVE_ADDR = 0x3c;
int SCCB_Init(int pin_sda, int pin_scl)
{
ESP_LOGI(TAG, "pin_sda %d pin_scl %d\n", pin_sda, pin_scl);
//log_i("SCCB_Init start");
ESP_LOGI(TAG, "pin_sda %d pin_scl %d", pin_sda, pin_scl);
i2c_config_t conf;
memset(&conf, 0, sizeof(i2c_config_t));
conf.mode = I2C_MODE_MASTER;
@ -56,10 +55,30 @@ int SCCB_Init(int pin_sda, int pin_scl)
return 0;
}
uint8_t SCCB_Probe()
int SCCB_Deinit(void)
{
return i2c_driver_delete(SCCB_I2C_PORT);
}
uint8_t SCCB_Probe(void)
{
uint8_t slave_addr = 0x0;
while(slave_addr < 0x7f) {
// for (size_t i = 1; i < 0x80; i++) {
// i2c_cmd_handle_t cmd = i2c_cmd_link_create();
// i2c_master_start(cmd);
// i2c_master_write_byte(cmd, ( i << 1 ) | WRITE_BIT, ACK_CHECK_EN);
// i2c_master_stop(cmd);
// esp_err_t ret = i2c_master_cmd_begin(SCCB_I2C_PORT, cmd, 1000 / portTICK_RATE_MS);
// i2c_cmd_link_delete(cmd);
// if( ret == ESP_OK) {
// ESP_LOGW(TAG, "Found I2C Device at 0x%02X", i);
// }
// }
for (size_t i = 0; i < CAMERA_MODEL_MAX; i++) {
if (slave_addr == camera_sensor[i].sccb_addr) {
continue;
}
slave_addr = camera_sensor[i].sccb_addr;
i2c_cmd_handle_t cmd = i2c_cmd_link_create();
i2c_master_start(cmd);
i2c_master_write_byte(cmd, ( slave_addr << 1 ) | WRITE_BIT, ACK_CHECK_EN);
@ -67,12 +86,10 @@ uint8_t SCCB_Probe()
esp_err_t ret = i2c_master_cmd_begin(SCCB_I2C_PORT, cmd, 1000 / portTICK_RATE_MS);
i2c_cmd_link_delete(cmd);
if( ret == ESP_OK) {
ESP_SLAVE_ADDR = slave_addr;
return ESP_SLAVE_ADDR;
return slave_addr;
}
slave_addr++;
}
return ESP_SLAVE_ADDR;
return 0;
}
uint8_t SCCB_Read(uint8_t slv_addr, uint8_t reg)

@ -10,6 +10,7 @@
#define __SCCB_H__
#include <stdint.h>
int SCCB_Init(int pin_sda, int pin_scl);
int SCCB_Deinit(void);
uint8_t SCCB_Probe();
uint8_t SCCB_Read(uint8_t slv_addr, uint8_t reg);
uint8_t SCCB_Write(uint8_t slv_addr, uint8_t reg, uint8_t data);

@ -1,5 +1,14 @@
#include "sensor.h"
const camera_sensor_info_t camera_sensor[CAMERA_MODEL_MAX] = {
{CAMERA_OV7725, OV7725_SCCB_ADDR, OV7725_PID, FRAMESIZE_VGA},
{CAMERA_OV2640, OV2640_SCCB_ADDR, OV2640_PID, FRAMESIZE_UXGA},
{CAMERA_OV3660, OV3660_SCCB_ADDR, OV3660_PID, FRAMESIZE_QXGA},
{CAMERA_OV5640, OV5640_SCCB_ADDR, OV5640_PID, FRAMESIZE_QSXGA},
{CAMERA_OV7670, OV7670_SCCB_ADDR, OV7670_PID, FRAMESIZE_VGA},
{CAMERA_NT99141, NT99141_SCCB_ADDR, NT99141_PID, FRAMESIZE_HD},
};
const resolution_info_t resolution[FRAMESIZE_INVALID] = {
{ 96, 96, ASPECT_RATIO_1X1 }, /* 96x96 */
{ 160, 120, ASPECT_RATIO_4X3 }, /* QQVGA */

@ -11,13 +11,45 @@
#include <stdint.h>
#include <stdbool.h>
#define NT99141_PID (0x14)
#define OV9650_PID (0x96)
#define OV7725_PID (0x77)
#define OV2640_PID (0x26)
#define OV3660_PID (0x36)
#define OV5640_PID (0x56)
#define OV7670_PID (0x76)
// Chip ID Registers
#define REG_PID 0x0A
#define REG_VER 0x0B
#define REG_MIDH 0x1C
#define REG_MIDL 0x1D
#define REG16_CHIDH 0x300A
#define REG16_CHIDL 0x300B
typedef enum {
OV9650_PID = 0x96,
OV7725_PID = 0x77,
OV2640_PID = 0x26,
OV3660_PID = 0x36,
OV5640_PID = 0x56,
OV7670_PID = 0x76,
NT99141_PID = 0x14
} camera_pid_t;
typedef enum {
CAMERA_OV7725,
CAMERA_OV2640,
CAMERA_OV3660,
CAMERA_OV5640,
CAMERA_OV7670,
CAMERA_NT99141,
CAMERA_MODEL_MAX,
CAMERA_NONE,
CAMERA_UNKNOWN
} camera_model_t;
typedef enum {
OV2640_SCCB_ADDR = 0x30,
OV5640_SCCB_ADDR = 0x3C,
OV3660_SCCB_ADDR = 0x3C,
OV7725_SCCB_ADDR = 0x21,
OV7670_SCCB_ADDR = 0x21,
NT99141_SCCB_ADDR = 0x2A,
} camera_sccb_addr_t;
typedef enum {
PIXFORMAT_RGB565, // 2BPP/RGB565
@ -58,6 +90,13 @@ typedef enum {
FRAMESIZE_INVALID
} framesize_t;
typedef struct {
const camera_model_t model;
const camera_sccb_addr_t sccb_addr;
const camera_pid_t pid;
const framesize_t max_size;
} camera_sensor_info_t;
typedef enum {
ASPECT_RATIO_4X3,
ASPECT_RATIO_3X2,
@ -101,6 +140,8 @@ typedef struct {
// Resolution table (in sensor.c)
extern const resolution_info_t resolution[];
// camera sensor table (in sensor.c)
extern const camera_sensor_info_t camera_sensor[];
typedef struct {
uint8_t MIDH;

@ -24,6 +24,10 @@
#if ESP_IDF_VERSION_MAJOR >= 4 // IDF 4+
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
#include "esp32/spiram.h"
#elif CONFIG_IDF_TARGET_ESP32S2
#include "esp32s2/spiram.h"
#elif CONFIG_IDF_TARGET_ESP32S3
#include "esp32s3/spiram.h"
#else
#error Target CONFIG_IDF_TARGET is not supported
#endif
@ -115,6 +119,54 @@ static bool _rgb_write(void * arg, uint16_t x, uint16_t y, uint16_t w, uint16_t
return true;
}
static bool _rgb565_write(void * arg, uint16_t x, uint16_t y, uint16_t w, uint16_t h, uint8_t *data)
{
rgb_jpg_decoder * jpeg = (rgb_jpg_decoder *)arg;
if(!data){
if(x == 0 && y == 0){
//write start
jpeg->width = w;
jpeg->height = h;
//if output is null, this is BMP
if(!jpeg->output){
jpeg->output = (uint8_t *)_malloc((w*h*3)+jpeg->data_offset);
if(!jpeg->output){
return false;
}
}
} else {
//write end
}
return true;
}
size_t jw = jpeg->width*3;
size_t jw2 = jpeg->width*2;
size_t t = y * jw;
size_t t2 = y * jw2;
size_t b = t + (h * jw);
size_t l = x * 2;
uint8_t *out = jpeg->output+jpeg->data_offset;
uint8_t *o = out;
size_t iy, iy2, ix, ix2;
w = w * 3;
for(iy=t, iy2=t2; iy<b; iy+=jw, iy2+=jw2) {
o = out+iy2+l;
for(ix2=ix=0; ix<w; ix+= 3, ix2 +=2) {
uint16_t r = data[ix];
uint16_t g = data[ix+1];
uint16_t b = data[ix+2];
uint16_t c = ((r & 0xF8) << 8) | ((g & 0xFC) << 3) | (b >> 3);
o[ix2+1] = c>>8;
o[ix2] = c&0xff;
}
data+=w;
}
return true;
}
//input buffer
static uint32_t _jpg_read(void * arg, size_t index, uint8_t *buf, size_t len)
{
@ -140,6 +192,21 @@ static bool jpg2rgb888(const uint8_t *src, size_t src_len, uint8_t * out, jpg_sc
return true;
}
bool jpg2rgb565(const uint8_t *src, size_t src_len, uint8_t * out, jpg_scale_t scale)
{
rgb_jpg_decoder jpeg;
jpeg.width = 0;
jpeg.height = 0;
jpeg.input = src;
jpeg.output = out;
jpeg.data_offset = 0;
if(esp_jpg_decode(src_len, scale, _jpg_read, _rgb565_write, (void*)&jpeg) != ESP_OK){
return false;
}
return true;
}
bool jpg2bmp(const uint8_t *src, size_t src_len, uint8_t ** out, size_t * out_len)
{

@ -25,6 +25,10 @@
#if ESP_IDF_VERSION_MAJOR >= 4 // IDF 4+
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
#include "esp32/spiram.h"
#elif CONFIG_IDF_TARGET_ESP32S2
#include "esp32s2/spiram.h"
#elif CONFIG_IDF_TARGET_ESP32S3
#include "esp32s3/spiram.h"
#else
#error Target CONFIG_IDF_TARGET is not supported
#endif
@ -195,7 +199,7 @@ public:
return true;
}
if ((size_t)len > (max_len - index)) {
ESP_LOGW(TAG, "JPG output overflow: %d bytes", len - (max_len - index));
//ESP_LOGW(TAG, "JPG output overflow: %d bytes (%d,%d,%d)", len - (max_len - index), len, index, max_len);
len = max_len - index;
}
if (len) {
@ -215,7 +219,7 @@ bool fmt2jpg(uint8_t *src, size_t src_len, uint16_t width, uint16_t height, pixf
{
//todo: allocate proper buffer for holding JPEG data
//this should be enough for CIF frame size
int jpg_buf_len = 64*1024;
int jpg_buf_len = 128*1024;
uint8_t * jpg_buf = (uint8_t *)_malloc(jpg_buf_len);

@ -1,432 +0,0 @@
/*
si2c.c - Software I2C library for ESP31B
Copyright (c) 2015 Hristo Gochkov. All rights reserved.
This file is part of the ESP31B core for Arduino environment.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include <stdint.h>
#include <stdbool.h>
#include "twi.h"
#include "soc/gpio_reg.h"
#include "soc/gpio_struct.h"
#include "soc/io_mux_reg.h"
#include "driver/rtc_io.h"
#include <stdio.h>
#define LOW 0x0
#define HIGH 0x1
//GPIO FUNCTIONS
#define INPUT 0x01
#define OUTPUT 0x02
#define PULLUP 0x04
#define INPUT_PULLUP 0x05
#define PULLDOWN 0x08
#define INPUT_PULLDOWN 0x09
#define OPEN_DRAIN 0x10
#define OUTPUT_OPEN_DRAIN 0x12
#define SPECIAL 0xF0
#define FUNCTION_1 0x00
#define FUNCTION_2 0x20
#define FUNCTION_3 0x40
#define FUNCTION_4 0x60
#define FUNCTION_5 0x80
#define FUNCTION_6 0xA0
#define ESP_REG(addr) *((volatile uint32_t *)(addr))
const uint8_t pin_to_mux[40] = { 0x44, 0x88, 0x40, 0x84, 0x48, 0x6c, 0x60, 0x64, 0x68, 0x54, 0x58, 0x5c, 0x34, 0x38, 0x30, 0x3c, 0x4c, 0x50, 0x70, 0x74, 0x78, 0x7c, 0x80, 0x8c, 0, 0x24, 0x28, 0x2c, 0, 0, 0, 0, 0x1c, 0x20, 0x14, 0x18, 0x04, 0x08, 0x0c, 0x10};
static void pinMode(uint8_t pin, uint8_t mode)
{
if(pin >= 40) {
return;
}
uint32_t rtc_reg = rtc_gpio_desc[pin].reg;
//RTC pins PULL settings
if(rtc_reg) {
//lock rtc
ESP_REG(rtc_reg) = ESP_REG(rtc_reg) & ~(rtc_gpio_desc[pin].mux);
if(mode & PULLUP) {
ESP_REG(rtc_reg) = (ESP_REG(rtc_reg) | rtc_gpio_desc[pin].pullup) & ~(rtc_gpio_desc[pin].pulldown);
} else if(mode & PULLDOWN) {
ESP_REG(rtc_reg) = (ESP_REG(rtc_reg) | rtc_gpio_desc[pin].pulldown) & ~(rtc_gpio_desc[pin].pullup);
} else {
ESP_REG(rtc_reg) = ESP_REG(rtc_reg) & ~(rtc_gpio_desc[pin].pullup | rtc_gpio_desc[pin].pulldown);
}
//unlock rtc
}
uint32_t pinFunction = 0, pinControl = 0;
//lock gpio
if(mode & INPUT) {
if(pin < 32) {
GPIO.enable_w1tc = BIT(pin);
} else {
GPIO.enable1_w1tc.val = BIT(pin - 32);
}
} else if(mode & OUTPUT) {
if(pin > 33) {
//unlock gpio
return;//pins above 33 can be only inputs
} else if(pin < 32) {
GPIO.enable_w1ts = BIT(pin);
} else {
GPIO.enable1_w1ts.val = BIT(pin - 32);
}
}
if(mode & PULLUP) {
pinFunction |= FUN_PU;
} else if(mode & PULLDOWN) {
pinFunction |= FUN_PD;
}
pinFunction |= ((uint32_t)2 << FUN_DRV_S);//what are the drivers?
pinFunction |= FUN_IE;//input enable but required for output as well?
if(mode & (INPUT | OUTPUT)) {
pinFunction |= ((uint32_t)2 << MCU_SEL_S);
} else if(mode == SPECIAL) {
pinFunction |= ((uint32_t)(((pin)==1||(pin)==3)?0:1) << MCU_SEL_S);
} else {
pinFunction |= ((uint32_t)(mode >> 5) << MCU_SEL_S);
}
ESP_REG(DR_REG_IO_MUX_BASE + pin_to_mux[pin]) = pinFunction;
if(mode & OPEN_DRAIN) {
pinControl = (1 << GPIO_PIN0_PAD_DRIVER_S);
}
GPIO.pin[pin].val = pinControl;
//unlock gpio
}
static void digitalWrite(uint8_t pin, uint8_t val)
{
if(val) {
if(pin < 32) {
GPIO.out_w1ts = BIT(pin);
} else if(pin < 34) {
GPIO.out1_w1ts.val = BIT(pin - 32);
}
} else {
if(pin < 32) {
GPIO.out_w1tc = BIT(pin);
} else if(pin < 34) {
GPIO.out1_w1tc.val = BIT(pin - 32);
}
}
}
unsigned char twi_dcount = 18;
static unsigned char twi_sda, twi_scl;
static inline void SDA_LOW()
{
//Enable SDA (becomes output and since GPO is 0 for the pin,
// it will pull the line low)
if (twi_sda < 32) {
GPIO.enable_w1ts = BIT(twi_sda);
} else {
GPIO.enable1_w1ts.val = BIT(twi_sda - 32);
}
}
static inline void SDA_HIGH()
{
//Disable SDA (becomes input and since it has pullup it will go high)
if (twi_sda < 32) {
GPIO.enable_w1tc = BIT(twi_sda);
} else {
GPIO.enable1_w1tc.val = BIT(twi_sda - 32);
}
}
static inline uint32_t SDA_READ()
{
if (twi_sda < 32) {
return (GPIO.in & BIT(twi_sda)) != 0;
} else {
return (GPIO.in1.val & BIT(twi_sda - 32)) != 0;
}
}
static void SCL_LOW()
{
if (twi_scl < 32) {
GPIO.enable_w1ts = BIT(twi_scl);
} else {
GPIO.enable1_w1ts.val = BIT(twi_scl - 32);
}
}
static void SCL_HIGH()
{
if (twi_scl < 32) {
GPIO.enable_w1tc = BIT(twi_scl);
} else {
GPIO.enable1_w1tc.val = BIT(twi_scl - 32);
}
}
static uint32_t SCL_READ()
{
if (twi_scl < 32) {
return (GPIO.in & BIT(twi_scl)) != 0;
} else {
return (GPIO.in1.val & BIT(twi_scl - 32)) != 0;
}
}
#ifndef FCPU80
#define FCPU80 80000000L
#endif
#if F_CPU == FCPU80
#define TWI_CLOCK_STRETCH 800
#else
#define TWI_CLOCK_STRETCH 1600
#endif
void twi_setClock(unsigned int freq)
{
#if F_CPU == FCPU80
if(freq <= 100000) {
twi_dcount = 19; //about 100KHz
} else if(freq <= 200000) {
twi_dcount = 8; //about 200KHz
} else if(freq <= 300000) {
twi_dcount = 3; //about 300KHz
} else if(freq <= 400000) {
twi_dcount = 1; //about 400KHz
} else {
twi_dcount = 1; //about 400KHz
}
#else
if(freq <= 100000) {
twi_dcount = 32; //about 100KHz
} else if(freq <= 200000) {
twi_dcount = 14; //about 200KHz
} else if(freq <= 300000) {
twi_dcount = 8; //about 300KHz
} else if(freq <= 400000) {
twi_dcount = 5; //about 400KHz
} else if(freq <= 500000) {
twi_dcount = 3; //about 500KHz
} else if(freq <= 600000) {
twi_dcount = 2; //about 600KHz
} else {
twi_dcount = 1; //about 700KHz
}
#endif
}
void twi_init(unsigned char sda, unsigned char scl)
{
twi_sda = sda;
twi_scl = scl;
pinMode(twi_sda, OUTPUT);
pinMode(twi_scl, OUTPUT);
digitalWrite(twi_sda, 0);
digitalWrite(twi_scl, 0);
pinMode(twi_sda, INPUT_PULLUP);
pinMode(twi_scl, INPUT_PULLUP);
twi_setClock(100000);
}
void twi_stop(void)
{
pinMode(twi_sda, INPUT);
pinMode(twi_scl, INPUT);
}
static void twi_delay(unsigned char v)
{
unsigned int i;
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-but-set-variable"
unsigned int reg;
for(i=0; i<v; i++) {
reg = REG_READ(GPIO_IN_REG);
}
#pragma GCC diagnostic pop
}
static bool twi_write_start(void)
{
SCL_HIGH();
SDA_HIGH();
if (SDA_READ() == 0) {
return false;
}
twi_delay(twi_dcount);
SDA_LOW();
twi_delay(twi_dcount);
return true;
}
static bool twi_write_stop(void)
{
unsigned int i = 0;
SCL_LOW();
SDA_LOW();
twi_delay(twi_dcount);
SCL_HIGH();
while (SCL_READ() == 0 && (i++) < TWI_CLOCK_STRETCH);// Clock stretching (up to 100us)
twi_delay(twi_dcount);
SDA_HIGH();
twi_delay(twi_dcount);
return true;
}
bool do_log = false;
static bool twi_write_bit(bool bit)
{
unsigned int i = 0;
SCL_LOW();
if (bit) {
SDA_HIGH();
if (do_log) {
twi_delay(twi_dcount+1);
}
} else {
SDA_LOW();
if (do_log) {}
}
twi_delay(twi_dcount+1);
SCL_HIGH();
while (SCL_READ() == 0 && (i++) < TWI_CLOCK_STRETCH);// Clock stretching (up to 100us)
twi_delay(twi_dcount);
return true;
}
static bool twi_read_bit(void)
{
unsigned int i = 0;
SCL_LOW();
SDA_HIGH();
twi_delay(twi_dcount+2);
SCL_HIGH();
while (SCL_READ() == 0 && (i++) < TWI_CLOCK_STRETCH);// Clock stretching (up to 100us)
bool bit = SDA_READ();
twi_delay(twi_dcount);
return bit;
}
static bool twi_write_byte(unsigned char byte)
{
if (byte == 0x43) {
// printf("TWB %02x ", (uint32_t) byte);
// do_log = true;
}
unsigned char bit;
for (bit = 0; bit < 8; bit++) {
twi_write_bit((byte & 0x80) != 0);
byte <<= 1;
}
if (do_log) {
printf("\n");
do_log = false;
}
return !twi_read_bit();//NACK/ACK
}
static unsigned char twi_read_byte(bool nack)
{
unsigned char byte = 0;
unsigned char bit;
for (bit = 0; bit < 8; bit++) {
byte = (byte << 1) | twi_read_bit();
}
twi_write_bit(nack);
return byte;
}
unsigned char twi_writeTo(unsigned char address, unsigned char * buf, unsigned int len, unsigned char sendStop)
{
unsigned int i;
if(!twi_write_start()) {
return 4; //line busy
}
if(!twi_write_byte(((address << 1) | 0) & 0xFF)) {
if (sendStop) {
twi_write_stop();
}
return 2; //received NACK on transmit of address
}
for(i=0; i<len; i++) {
if(!twi_write_byte(buf[i])) {
if (sendStop) {
twi_write_stop();
}
return 3;//received NACK on transmit of data
}
}
if(sendStop) {
twi_write_stop();
}
i = 0;
while(SDA_READ() == 0 && (i++) < 10) {
SCL_LOW();
twi_delay(twi_dcount);
SCL_HIGH();
twi_delay(twi_dcount);
}
return 0;
}
unsigned char twi_readFrom(unsigned char address, unsigned char* buf, unsigned int len, unsigned char sendStop)
{
unsigned int i;
if(!twi_write_start()) {
return 4; //line busy
}
if(!twi_write_byte(((address << 1) | 1) & 0xFF)) {
if (sendStop) {
twi_write_stop();
}
return 2;//received NACK on transmit of address
}
for(i=0; i<(len-1); i++) {
buf[i] = twi_read_byte(false);
}
buf[len-1] = twi_read_byte(true);
if(sendStop) {
twi_write_stop();
}
i = 0;
while(SDA_READ() == 0 && (i++) < 10) {
SCL_LOW();
twi_delay(twi_dcount);
SCL_HIGH();
twi_delay(twi_dcount);
}
return 0;
}

@ -1,38 +0,0 @@
/*
twi.h - Software I2C library for ESP31B
Copyright (c) 2015 Hristo Gochkov. All rights reserved.
This file is part of the ESP31B core for Arduino environment.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifndef SI2C_h
#define SI2C_h
#ifdef __cplusplus
extern "C" {
#endif
void twi_init(unsigned char sda, unsigned char scl);
void twi_stop(void);
void twi_setClock(unsigned int freq);
uint8_t twi_writeTo(unsigned char address, unsigned char * buf, unsigned int len, unsigned char sendStop);
uint8_t twi_readFrom(unsigned char address, unsigned char * buf, unsigned int len, unsigned char sendStop);
#ifdef __cplusplus
}
#endif
#endif

@ -15,9 +15,13 @@ static const char* TAG = "camera_xclk";
esp_err_t xclk_timer_conf(int ledc_timer, int xclk_freq_hz)
{
ledc_timer_config_t timer_conf;
timer_conf.duty_resolution = 2;
timer_conf.duty_resolution = LEDC_TIMER_1_BIT;
timer_conf.freq_hz = xclk_freq_hz;
#if CONFIG_IDF_TARGET_ESP32
timer_conf.speed_mode = LEDC_HIGH_SPEED_MODE;
#else
timer_conf.speed_mode = LEDC_LOW_SPEED_MODE;
#endif
#if ESP_IDF_VERSION_MAJOR >= 4
timer_conf.clk_cfg = LEDC_AUTO_CLK;
#endif
@ -41,11 +45,15 @@ esp_err_t camera_enable_out_clock(camera_config_t* config)
ledc_channel_config_t ch_conf;
ch_conf.gpio_num = config->pin_xclk;
#if CONFIG_IDF_TARGET_ESP32
ch_conf.speed_mode = LEDC_HIGH_SPEED_MODE;
#else
ch_conf.speed_mode = LEDC_LOW_SPEED_MODE;
#endif
ch_conf.channel = config->ledc_channel;
ch_conf.intr_type = LEDC_INTR_DISABLE;
ch_conf.timer_sel = config->ledc_timer;
ch_conf.duty = 2;
ch_conf.duty = 1;
ch_conf.hpoint = 0;
err = ledc_channel_config(&ch_conf);
if (err != ESP_OK) {

@ -0,0 +1 @@
*.DS_Store

@ -0,0 +1,61 @@
if(IDF_TARGET STREQUAL "esp32" OR IDF_TARGET STREQUAL "esp32s2" OR IDF_TARGET STREQUAL "esp32s3")
set(COMPONENT_SRCS
driver/esp_camera.c
driver/cam_hal.c
driver/sccb.c
driver/sensor.c
sensors/ov2640.c
sensors/ov3660.c
sensors/ov5640.c
sensors/ov7725.c
sensors/ov7670.c
sensors/nt99141.c
conversions/yuv.c
conversions/to_jpg.cpp
conversions/to_bmp.c
conversions/jpge.cpp
conversions/esp_jpg_decode.c
)
set(COMPONENT_ADD_INCLUDEDIRS
driver/include
conversions/include
)
set(COMPONENT_PRIV_INCLUDEDIRS
driver/private_include
sensors/private_include
conversions/private_include
target/private_include
)
if(IDF_TARGET STREQUAL "esp32")
list(APPEND COMPONENT_SRCS
target/xclk.c
target/esp32/ll_cam.c
)
endif()
if(IDF_TARGET STREQUAL "esp32s2")
list(APPEND COMPONENT_SRCS
target/xclk.c
target/esp32s2/ll_cam.c
target/esp32s2/tjpgd.c
)
list(APPEND COMPONENT_PRIV_INCLUDEDIRS
target/esp32s2/private_include
)
endif()
if(IDF_TARGET STREQUAL "esp32s3")
list(APPEND COMPONENT_SRCS
target/esp32s3/ll_cam.c
)
endif()
set(COMPONENT_REQUIRES driver)
set(COMPONENT_PRIV_REQUIRES freertos nvs_flash)
register_component()
endif()

@ -1,65 +1,71 @@
menu "Camera configuration"
config OV2640_SUPPORT
bool "OV2640 Support"
default y
help
Enable this option if you want to use the OV2640.
Disable this option to save memory.
config OV7725_SUPPORT
bool "OV7725 Support"
default n
help
Enable this option if you want to use the OV7725.
Disable this option to save memory.
config OV3660_SUPPORT
bool "OV3660 Support"
default y
help
Enable this option if you want to use the OV3360.
Disable this option to save memory.
config OV5640_SUPPORT
bool "OV5640 Support"
default y
help
Enable this option if you want to use the OV5640.
Disable this option to save memory.
config SCCB_HARDWARE_I2C
bool "Use hardware I2C for SCCB"
default y
help
Enable this option if you want to use hardware I2C to control the camera.
Disable this option to use software I2C.
choice SCCB_HARDWARE_I2C_PORT
bool "I2C peripheral to use for SCCB"
depends on SCCB_HARDWARE_I2C
default SCCB_HARDWARE_I2C_PORT1
config OV7670_SUPPORT
bool "Support OV7670 VGA"
default y
help
Enable this option if you want to use the OV7670.
Disable this option to save memory.
config SCCB_HARDWARE_I2C_PORT0
bool "I2C0"
config SCCB_HARDWARE_I2C_PORT1
bool "I2C1"
config OV7725_SUPPORT
bool "Support OV7725 SVGA"
default n
help
Enable this option if you want to use the OV7725.
Disable this option to save memory.
endchoice
config NT99141_SUPPORT
bool "Support NT99141 HD"
default y
help
Enable this option if you want to use the NT99141.
Disable this option to save memory.
choice CAMERA_TASK_PINNED_TO_CORE
bool "Camera task pinned to core"
default CAMERA_CORE0
help
Pin the camera handle task to a certain core(0/1). It can also be done automatically choosing NO_AFFINITY.
config OV2640_SUPPORT
bool "Support OV2640 2MP"
default y
help
Enable this option if you want to use the OV2640.
Disable this option to save memory.
config CAMERA_CORE0
bool "CORE0"
config CAMERA_CORE1
bool "CORE1"
config CAMERA_NO_AFFINITY
bool "NO_AFFINITY"
config OV3660_SUPPORT
bool "Support OV3660 3MP"
default y
help
Enable this option if you want to use the OV3360.
Disable this option to save memory.
config OV5640_SUPPORT
bool "Support OV5640 5MP"
default y
help
Enable this option if you want to use the OV5640.
Disable this option to save memory.
choice SCCB_HARDWARE_I2C_PORT
bool "I2C peripheral to use for SCCB"
default SCCB_HARDWARE_I2C_PORT1
config SCCB_HARDWARE_I2C_PORT0
bool "I2C0"
config SCCB_HARDWARE_I2C_PORT1
bool "I2C1"
endchoice
choice CAMERA_TASK_PINNED_TO_CORE
bool "Camera task pinned to core"
default CAMERA_CORE0
help
Pin the camera handle task to a certain core(0/1). It can also be done automatically choosing NO_AFFINITY.
config CAMERA_CORE0
bool "CORE0"
config CAMERA_CORE1
bool "CORE1"
config CAMERA_NO_AFFINITY
bool "NO_AFFINITY"
endchoice
endchoice
endmenu

@ -1,16 +1,358 @@
# ESP32 MJPEG Multiclient Streaming Server
# ESP32 Camera Driver
This is a simple MJPEG streaming webserver implemented for AI-Thinker ESP32-CAM or ESP-EYE modules.
## General Information
This is tested to work with **VLC** and **Blynk** video widget.
This repository hosts ESP32, ESP32-S2 and ESP32-S3 compatible driver for OV2640, OV3660, OV5640, OV7670 and OV7725 image sensors. Additionally it provides a few tools, which allow converting the captured frame data to the more common BMP and JPEG formats.
## Important to Remember
- Except when using CIF or lower resolution with JPEG, the driver requires PSRAM to be installed and activated.
- Using YUV or RGB puts a lot of strain on the chip because writing to PSRAM is not particularly fast. The result is that image data might be missing. This is particularly true if WiFi is enabled. If you need RGB data, it is recommended that JPEG is captured and then turned into RGB using `fmt2rgb888` or `fmt2bmp`/`frame2bmp`.
- When 1 frame buffer is used, the driver will wait for the current frame to finish (VSYNC) and start I2S DMA. After the frame is acquired, I2S will be stopped and the frame buffer returned to the application. This approach gives more control over the system, but results in longer time to get the frame.
- When 2 or more frame bufers are used, I2S is running in continuous mode and each frame is pushed to a queue that the application can access. This approach puts more strain on the CPU/Memory, but allows for double the frame rate. Please use only with JPEG.
**This version uses FreeRTOS tasks to enable streaming to up to 10 connected clients**
## Installation Instructions
### Using esp-idf
Inspired by and based on this Instructable: [$9 RTSP Video Streamer Using the ESP32-CAM Board](https://www.instructables.com/id/9-RTSP-Video-Streamer-Using-the-ESP32-CAM-Board/)
- Clone or download and extract the repository to the components folder of your ESP-IDF project
- Enable PSRAM in `menuconfig` (also set Flash and PSRAM frequiencies to 80MHz)
- Include `esp_camera.h` in your code
### Using PlatformIO
The easy way -- on the `env` section of `platformio.ini`, add the following:
```ini
[env]
lib_deps =
esp32-camera
```
Now the `esp_camera.h` is available to be included:
```c
#include "esp_camera.h"
```
Enable PSRAM on `menuconfig` or type it direclty on `sdkconfig`. Check the [official doc](https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-reference/kconfig.html#config-esp32-spiram-support) for more info.
```
CONFIG_ESP32_SPIRAM_SUPPORT=y
```
***Arduino*** The easy-way (content above) only seems to work if you're using `framework=arduino` which seems to take a bunch of the guesswork out (thanks Arduino!) but also suck up a lot more memory and flash, almost crippling the performance. If you plan to use the `framework=espidf` then read the sections below carefully!!
## Platform.io lib/submodule (for framework=espidf)
It's probably easier to just skip the platform.io library registry version and link the git repo as a submodule. (i.e. using code outside the platform.io library management). In this example we will install this as a submodule inside the platform.io $project/lib folder:
```
cd $project\lib
git submodule add -b master https://github.com/espressif/esp32-camera.git
```
Then in `platformio.ini` file
```
build_flags =
-I../lib/esp32-camera
```
After that `#include "esp_camera.h"` statement will be available. Now the module is included, and you're hopefully back to the same place as the easy-Arduino way.
**Warning about platform.io/espidf and fresh (not initialized) git repos**
There is a sharp-edge on you'll discover in the platform.io build process (in espidf v3.3 & 4.0.1) where a project which has only had `git init` but nothing committed will crash platform.io build process with highly non-useful output. The cause is due to lack of a version (making you think you did something wrong, when you didn't at all) - the output is horribly non-descript. Solution: the devs want you to create a file called version.txt with a number in it, or simply commit any file to the projects git repo and use git. This happens because platform.io build process tries to be too clever and determine the build version number from the git repo - it's a sharp edge you'll only encounter if you're experimenting on a new project with no commits .. like wtf is my camera not working let's try a 'clean project'?! </rant>
## Platform.io Kconfig
Kconfig is used by the platform.io menuconfig (accessed by running: `pio run -t menuconfig`) to interactively manage the various #ifdef statements throughout the espidf and supporting libraries (i.e. this repo: esp32-camera and arduino-esp32.git). The menuconfig process generates the `sdkconfig` file which is ultimately used behind the scenes by espidf compile+build process.
**Make sure to append or symlink** [this `Kconfig`](./Kconfig) content into the `Kconfig` of your project.
You symlink (or copy) the included Kconfig into your platform.io projects src directory. The file should be named `Kconfig.projbuild` in your projects src\ directory or you could also add the library path to a CMakefile.txt and hope the `Kconfig` (or `Kconfig.projbuild`) gets discovered by the menuconfig process, though this unpredictable for me.
The unpredictable wonky behavior in platform.io build process around Kconfig naming (Kconfig vs. Kconfig.projbuild) occurs between espidf versions 3.3 and 4.0 - but if you don't see "Camera configuration" in your `pio run -t menuconfig` then there is no point trying to test camera code (it may compile, but it probably won't work!) and it seems the platform.io devs (when they built their wrapper around the espidf menuconfig) didn't implement it properly. You've probably already figured out you can't use the espidf build tools since the files are in totally different locations and also different versions with sometimes different syntax. This is one of those times you might consider changing the `platformio.ini` from `platform=espressif32` to `platform=https://github.com/platformio/platform-espressif32.git#develop` to get a more recent version of the espidf 4.0 tools.
However with a bit of patience and experimenting you'll figure the Kconfig out. Once Kconfig (or Kconfig.projbuild) is working then you will be able to choose the configurations according to your setup or the camera libraries will be compiled. Although you might also need to delete your .pio/build directory before the options appear .. again, the `pio run -t menuconfig` doens't always notice the new Kconfig files!
If you miss-skip-ignore this critical step the camera module will compile but camera logic inside the library will be 'empty' because the Kconfig sets the proper #ifdef statements during the build process to initialize the selected cameras. It's very not optional!
### Kconfig options
| config | description | default |
| --------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------ |
| CONFIG_OV2640_SUPPORT | Support for OV2640 camera | enabled |
| CONFIG_OV7725_SUPPORT | Support for OV7725 camera | disabled |
| CONFIG_OV3660_SUPPORT | Support for OV3660 camera | enabled |
| CONFIG_OV5640_SUPPORT | Support for OV5640 camera | enabled |
| CONFIG_SCCB_HARDWARE_I2C | Enable this option if you want to use hardware I2C to control the camera. Disable this option to use software I2C. | enabled |
| CONFIG_SCCB_HARDWARE_I2C_PORT | I2C peripheral to use for SCCB. Can be I2C0 and I2C1. | CONFIG_SCCB_HARDWARE_I2C_PORT1 |
| CONFIG_CAMERA_TASK_PINNED_TO_CORE | Pin the camera handle task to a certain core(0/1). It can also be done automatically choosing NO_AFFINITY. Can be CAMERA_CORE0, CAMERA_CORE1 or NO_AFFINITY. | CONFIG_CAMERA_CORE0 |
## Examples
### Initialization
```c
#include "esp_camera.h"
//WROVER-KIT PIN Map
#define CAM_PIN_PWDN -1 //power down is not used
#define CAM_PIN_RESET -1 //software reset will be performed
#define CAM_PIN_XCLK 21
#define CAM_PIN_SIOD 26
#define CAM_PIN_SIOC 27
#define CAM_PIN_D7 35
#define CAM_PIN_D6 34
#define CAM_PIN_D5 39
#define CAM_PIN_D4 36
#define CAM_PIN_D3 19
#define CAM_PIN_D2 18
#define CAM_PIN_D1 5
#define CAM_PIN_D0 4
#define CAM_PIN_VSYNC 25
#define CAM_PIN_HREF 23
#define CAM_PIN_PCLK 22
static camera_config_t camera_config = {
.pin_pwdn = CAM_PIN_PWDN,
.pin_reset = CAM_PIN_RESET,
.pin_xclk = CAM_PIN_XCLK,
.pin_sscb_sda = CAM_PIN_SIOD,
.pin_sscb_scl = CAM_PIN_SIOC,
.pin_d7 = CAM_PIN_D7,
.pin_d6 = CAM_PIN_D6,
.pin_d5 = CAM_PIN_D5,
.pin_d4 = CAM_PIN_D4,
.pin_d3 = CAM_PIN_D3,
.pin_d2 = CAM_PIN_D2,
.pin_d1 = CAM_PIN_D1,
.pin_d0 = CAM_PIN_D0,
.pin_vsync = CAM_PIN_VSYNC,
.pin_href = CAM_PIN_HREF,
.pin_pclk = CAM_PIN_PCLK,
.xclk_freq_hz = 20000000,//EXPERIMENTAL: Set to 16MHz on ESP32-S2 or ESP32-S3 to enable EDMA mode
.ledc_timer = LEDC_TIMER_0,
.ledc_channel = LEDC_CHANNEL_0,
.pixel_format = PIXFORMAT_JPEG,//YUV422,GRAYSCALE,RGB565,JPEG
.frame_size = FRAMESIZE_UXGA,//QQVGA-QXGA Do not use sizes above QVGA when not JPEG
.jpeg_quality = 12, //0-63 lower number means higher quality
.fb_count = 1, //if more than one, i2s runs in continuous mode. Use only with JPEG
.grab_mode = CAMERA_GRAB_WHEN_EMPTY//CAMERA_GRAB_LATEST. Sets when buffers should be filled
};
esp_err_t camera_init(){
//power up the camera if PWDN pin is defined
if(CAM_PIN_PWDN != -1){
pinMode(CAM_PIN_PWDN, OUTPUT);
digitalWrite(CAM_PIN_PWDN, LOW);
}
//initialize the camera
esp_err_t err = esp_camera_init(&camera_config);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Camera Init Failed");
return err;
}
return ESP_OK;
}
esp_err_t camera_capture(){
//acquire a frame
camera_fb_t * fb = esp_camera_fb_get();
if (!fb) {
ESP_LOGE(TAG, "Camera Capture Failed");
return ESP_FAIL;
}
//replace this with your own function
process_image(fb->width, fb->height, fb->format, fb->buf, fb->len);
//return the frame buffer back to the driver for reuse
esp_camera_fb_return(fb);
return ESP_OK;
}
```
### JPEG HTTP Capture
```c
#include "esp_camera.h"
#include "esp_http_server.h"
#include "esp_timer.h"
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;
}
esp_err_t jpg_httpd_handler(httpd_req_t *req){
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(TAG, "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(TAG, "JPG: %uKB %ums", (uint32_t)(fb_len/1024), (uint32_t)((fr_end - fr_start)/1000));
return res;
}
```
### JPEG HTTP Stream
```c
#include "esp_camera.h"
#include "esp_http_server.h"
#include "esp_timer.h"
#define PART_BOUNDARY "123456789000000000000987654321"
static const char* _STREAM_CONTENT_TYPE = "multipart/x-mixed-replace;boundary=" PART_BOUNDARY;
static const char* _STREAM_BOUNDARY = "\r\n--" PART_BOUNDARY "\r\n";
static const char* _STREAM_PART = "Content-Type: image/jpeg\r\nContent-Length: %u\r\n\r\n";
esp_err_t jpg_stream_httpd_handler(httpd_req_t *req){
camera_fb_t * fb = NULL;
esp_err_t res = ESP_OK;
size_t _jpg_buf_len;
uint8_t * _jpg_buf;
char * part_buf[64];
static int64_t last_frame = 0;
if(!last_frame) {
last_frame = esp_timer_get_time();
}
res = httpd_resp_set_type(req, _STREAM_CONTENT_TYPE);
if(res != ESP_OK){
return res;
}
while(true){
fb = esp_camera_fb_get();
if (!fb) {
ESP_LOGE(TAG, "Camera capture failed");
res = ESP_FAIL;
break;
}
if(fb->format != PIXFORMAT_JPEG){
bool jpeg_converted = frame2jpg(fb, 80, &_jpg_buf, &_jpg_buf_len);
if(!jpeg_converted){
ESP_LOGE(TAG, "JPEG compression failed");
esp_camera_fb_return(fb);
res = ESP_FAIL;
}
} else {
_jpg_buf_len = fb->len;
_jpg_buf = fb->buf;
}
if(res == ESP_OK){
res = httpd_resp_send_chunk(req, _STREAM_BOUNDARY, strlen(_STREAM_BOUNDARY));
}
if(res == ESP_OK){
size_t hlen = snprintf((char *)part_buf, 64, _STREAM_PART, _jpg_buf_len);
res = httpd_resp_send_chunk(req, (const char *)part_buf, hlen);
}
if(res == ESP_OK){
res = httpd_resp_send_chunk(req, (const char *)_jpg_buf, _jpg_buf_len);
}
if(fb->format != PIXFORMAT_JPEG){
free(_jpg_buf);
}
esp_camera_fb_return(fb);
if(res != ESP_OK){
break;
}
int64_t fr_end = esp_timer_get_time();
int64_t frame_time = fr_end - last_frame;
last_frame = fr_end;
frame_time /= 1000;
ESP_LOGI(TAG, "MJPG: %uKB %ums (%.1ffps)",
(uint32_t)(_jpg_buf_len/1024),
(uint32_t)frame_time, 1000.0 / (uint32_t)frame_time);
}
last_frame = 0;
return res;
}
```
### BMP HTTP Capture
```c
#include "esp_camera.h"
#include "esp_http_server.h"
#include "esp_timer.h"
esp_err_t bmp_httpd_handler(httpd_req_t *req){
camera_fb_t * fb = NULL;
esp_err_t res = ESP_OK;
int64_t fr_start = esp_timer_get_time();
fb = esp_camera_fb_get();
if (!fb) {
ESP_LOGE(TAG, "Camera capture failed");
httpd_resp_send_500(req);
return ESP_FAIL;
}
uint8_t * buf = NULL;
size_t buf_len = 0;
bool converted = frame2bmp(fb, &buf, &buf_len);
esp_camera_fb_return(fb);
if(!converted){
ESP_LOGE(TAG, "BMP conversion failed");
httpd_resp_send_500(req);
return ESP_FAIL;
}
res = httpd_resp_set_type(req, "image/x-windows-bmp")
|| httpd_resp_set_hdr(req, "Content-Disposition", "inline; filename=capture.bmp")
|| httpd_resp_send(req, (const char *)buf, buf_len);
free(buf);
int64_t fr_end = esp_timer_get_time();
ESP_LOGI(TAG, "BMP: %uKB %ums", (uint32_t)(buf_len/1024), (uint32_t)((fr_end - fr_start)/1000));
return res;
}
```

@ -0,0 +1,472 @@
// Copyright 2010-2020 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.
#include <stdio.h>
#include <string.h>
#include "esp_heap_caps.h"
#include "ll_cam.h"
#include "cam_hal.h"
static const char *TAG = "cam_hal";
static cam_obj_t *cam_obj = NULL;
static const uint32_t JPEG_SOI_MARKER = 0xFFD8FF; // written in little-endian for esp32
static const uint16_t JPEG_EOI_MARKER = 0xD9FF; // written in little-endian for esp32
static int cam_verify_jpeg_soi(const uint8_t *inbuf, uint32_t length)
{
uint32_t sig = *((uint32_t *)inbuf) & 0xFFFFFF;
if(sig != JPEG_SOI_MARKER) {
for (uint32_t i = 0; i < length; i++) {
sig = *((uint32_t *)(&inbuf[i])) & 0xFFFFFF;
if (sig == JPEG_SOI_MARKER) {
ESP_LOGW(TAG, "SOI: %d", i);
return i;
}
}
ESP_LOGW(TAG, "NO-SOI");
return -1;
}
return 0;
}
static int cam_verify_jpeg_eoi(const uint8_t *inbuf, uint32_t length)
{
int offset = -1;
uint8_t *dptr = (uint8_t *)inbuf + length - 2;
while (dptr > inbuf) {
uint16_t sig = *((uint16_t *)dptr);
if (JPEG_EOI_MARKER == sig) {
offset = dptr - inbuf;
//ESP_LOGW(TAG, "EOI: %d", length - (offset + 2));
return offset;
}
dptr--;
}
return -1;
}
static bool cam_get_next_frame(int * frame_pos)
{
if(!cam_obj->frames[*frame_pos].en){
for (int x = 0; x < cam_obj->frame_cnt; x++) {
if (cam_obj->frames[x].en) {
*frame_pos = x;
return true;
}
}
} else {
return true;
}
return false;
}
static bool cam_start_frame(int * frame_pos)
{
if (cam_get_next_frame(frame_pos)) {
if(ll_cam_start(cam_obj, *frame_pos)){
// Vsync the frame manually
ll_cam_do_vsync(cam_obj);
uint64_t us = (uint64_t)esp_timer_get_time();
cam_obj->frames[*frame_pos].fb.timestamp.tv_sec = us / 1000000UL;
cam_obj->frames[*frame_pos].fb.timestamp.tv_usec = us % 1000000UL;
return true;
}
}
return false;
}
void IRAM_ATTR ll_cam_send_event(cam_obj_t *cam, cam_event_t cam_event, BaseType_t * HPTaskAwoken)
{
if (xQueueSendFromISR(cam->event_queue, (void *)&cam_event, HPTaskAwoken) != pdTRUE) {
ll_cam_stop(cam);
cam->state = CAM_STATE_IDLE;
ESP_EARLY_LOGE(TAG, "EV-OVF");
}
}
//Copy fram from DMA dma_buffer to fram dma_buffer
static void cam_task(void *arg)
{
int cnt = 0;
int frame_pos = 0;
cam_obj->state = CAM_STATE_IDLE;
cam_event_t cam_event = 0;
xQueueReset(cam_obj->event_queue);
while (1) {
xQueueReceive(cam_obj->event_queue, (void *)&cam_event, portMAX_DELAY);
DBG_PIN_SET(1);
switch (cam_obj->state) {
case CAM_STATE_IDLE: {
if (cam_event == CAM_VSYNC_EVENT) {
//DBG_PIN_SET(1);
if(cam_start_frame(&frame_pos)){
cam_obj->frames[frame_pos].fb.len = 0;
cam_obj->state = CAM_STATE_READ_BUF;
}
cnt = 0;
}
}
break;
case CAM_STATE_READ_BUF: {
camera_fb_t * frame_buffer_event = &cam_obj->frames[frame_pos].fb;
size_t pixels_per_dma = (cam_obj->dma_half_buffer_size * cam_obj->fb_bytes_per_pixel) / (cam_obj->dma_bytes_per_item * cam_obj->in_bytes_per_pixel);
if (cam_event == CAM_IN_SUC_EOF_EVENT) {
if(!cam_obj->psram_mode){
if (cam_obj->fb_size < (frame_buffer_event->len + pixels_per_dma)) {
ESP_LOGW(TAG, "FB-OVF");
ll_cam_stop(cam_obj);
DBG_PIN_SET(0);
continue;
}
frame_buffer_event->len += ll_cam_memcpy(cam_obj,
&frame_buffer_event->buf[frame_buffer_event->len],
&cam_obj->dma_buffer[(cnt % cam_obj->dma_half_buffer_cnt) * cam_obj->dma_half_buffer_size],
cam_obj->dma_half_buffer_size);
}
//Check for JPEG SOI in the first buffer. stop if not found
if (cam_obj->jpeg_mode && cnt == 0 && cam_verify_jpeg_soi(frame_buffer_event->buf, frame_buffer_event->len) != 0) {
ll_cam_stop(cam_obj);
cam_obj->state = CAM_STATE_IDLE;
}
cnt++;
} else if (cam_event == CAM_VSYNC_EVENT) {
//DBG_PIN_SET(1);
ll_cam_stop(cam_obj);
if (cnt || !cam_obj->jpeg_mode || cam_obj->psram_mode) {
if (cam_obj->jpeg_mode) {
if (!cam_obj->psram_mode) {
if (cam_obj->fb_size < (frame_buffer_event->len + pixels_per_dma)) {
ESP_LOGW(TAG, "FB-OVF");
cnt--;
} else {
frame_buffer_event->len += ll_cam_memcpy(cam_obj,
&frame_buffer_event->buf[frame_buffer_event->len],
&cam_obj->dma_buffer[(cnt % cam_obj->dma_half_buffer_cnt) * cam_obj->dma_half_buffer_size],
cam_obj->dma_half_buffer_size);
}
}
cnt++;
}
cam_obj->frames[frame_pos].en = 0;
if (cam_obj->psram_mode) {
if (cam_obj->jpeg_mode) {
frame_buffer_event->len = cnt * cam_obj->dma_half_buffer_size;
} else {
frame_buffer_event->len = cam_obj->recv_size;
}
} else if (!cam_obj->jpeg_mode) {
if (frame_buffer_event->len != cam_obj->fb_size) {
cam_obj->frames[frame_pos].en = 1;
ESP_LOGE(TAG, "FB-SIZE: %u != %u", frame_buffer_event->len, cam_obj->fb_size);
}
}
//send frame
if(!cam_obj->frames[frame_pos].en && xQueueSend(cam_obj->frame_buffer_queue, (void *)&frame_buffer_event, 0) != pdTRUE) {
//pop frame buffer from the queue
camera_fb_t * fb2 = NULL;
if(xQueueReceive(cam_obj->frame_buffer_queue, &fb2, 0) == pdTRUE) {
//push the new frame to the end of the queue
if (xQueueSend(cam_obj->frame_buffer_queue, (void *)&frame_buffer_event, 0) != pdTRUE) {
cam_obj->frames[frame_pos].en = 1;
ESP_LOGE(TAG, "FBQ-SND");
}
//free the popped buffer
cam_give(fb2);
} else {
//queue is full and we could not pop a frame from it
cam_obj->frames[frame_pos].en = 1;
ESP_LOGE(TAG, "FBQ-RCV");
}
}
}
if(!cam_start_frame(&frame_pos)){
cam_obj->state = CAM_STATE_IDLE;
} else {
cam_obj->frames[frame_pos].fb.len = 0;
}
cnt = 0;
}
}
break;
}
DBG_PIN_SET(0);
}
}
static lldesc_t * allocate_dma_descriptors(uint32_t count, uint16_t size, uint8_t * buffer)
{
lldesc_t *dma = (lldesc_t *)heap_caps_malloc(count * sizeof(lldesc_t), MALLOC_CAP_DMA);
if (dma == NULL) {
return dma;
}
for (int x = 0; x < count; x++) {
dma[x].size = size;
dma[x].length = 0;
dma[x].sosf = 0;
dma[x].eof = 0;
dma[x].owner = 1;
dma[x].buf = (buffer + size * x);
dma[x].empty = (uint32_t)&dma[(x + 1) % count];
}
return dma;
}
static esp_err_t cam_dma_config()
{
bool ret = ll_cam_dma_sizes(cam_obj);
if (0 == ret) {
return ESP_FAIL;
}
cam_obj->dma_node_cnt = (cam_obj->dma_buffer_size) / cam_obj->dma_node_buffer_size; // Number of DMA nodes
cam_obj->frame_copy_cnt = cam_obj->recv_size / cam_obj->dma_half_buffer_size; // Number of interrupted copies, ping-pong copy
ESP_LOGI(TAG, "buffer_size: %d, half_buffer_size: %d, node_buffer_size: %d, node_cnt: %d, total_cnt: %d",
cam_obj->dma_buffer_size, cam_obj->dma_half_buffer_size, cam_obj->dma_node_buffer_size, cam_obj->dma_node_cnt, cam_obj->frame_copy_cnt);
cam_obj->dma_buffer = NULL;
cam_obj->dma = NULL;
cam_obj->frames = (cam_frame_t *)heap_caps_calloc(1, cam_obj->frame_cnt * sizeof(cam_frame_t), MALLOC_CAP_DEFAULT);
CAM_CHECK(cam_obj->frames != NULL, "frames malloc failed", ESP_FAIL);
uint8_t dma_align = 0;
size_t fb_size = cam_obj->fb_size;
if (cam_obj->psram_mode) {
dma_align = ll_cam_get_dma_align(cam_obj);
if (cam_obj->fb_size < cam_obj->recv_size) {
fb_size = cam_obj->recv_size;
}
}
for (int x = 0; x < cam_obj->frame_cnt; x++) {
cam_obj->frames[x].dma = NULL;
cam_obj->frames[x].fb_offset = 0;
cam_obj->frames[x].en = 0;
cam_obj->frames[x].fb.buf = (uint8_t *)heap_caps_malloc(fb_size * sizeof(uint8_t) + dma_align, MALLOC_CAP_SPIRAM);
CAM_CHECK(cam_obj->frames[x].fb.buf != NULL, "frame buffer malloc failed", ESP_FAIL);
if (cam_obj->psram_mode) {
//align PSRAM buffer. TODO: save the offset so proper address can be freed later
cam_obj->frames[x].fb_offset = dma_align - ((uint32_t)cam_obj->frames[x].fb.buf & (dma_align - 1));
cam_obj->frames[x].fb.buf += cam_obj->frames[x].fb_offset;
ESP_LOGI(TAG, "Frame[%d]: Offset: %u, Addr: 0x%08X", x, cam_obj->frames[x].fb_offset, (uint32_t)cam_obj->frames[x].fb.buf);
cam_obj->frames[x].dma = allocate_dma_descriptors(cam_obj->dma_node_cnt, cam_obj->dma_node_buffer_size, cam_obj->frames[x].fb.buf);
CAM_CHECK(cam_obj->frames[x].dma != NULL, "frame dma malloc failed", ESP_FAIL);
}
cam_obj->frames[x].en = 1;
}
if (!cam_obj->psram_mode) {
cam_obj->dma_buffer = (uint8_t *)heap_caps_malloc(cam_obj->dma_buffer_size * sizeof(uint8_t), MALLOC_CAP_DMA);
CAM_CHECK(cam_obj->dma_buffer != NULL, "dma_buffer malloc failed", ESP_FAIL);
cam_obj->dma = allocate_dma_descriptors(cam_obj->dma_node_cnt, cam_obj->dma_node_buffer_size, cam_obj->dma_buffer);
CAM_CHECK(cam_obj->dma != NULL, "dma malloc failed", ESP_FAIL);
}
return ESP_OK;
}
esp_err_t cam_init(const camera_config_t *config)
{
CAM_CHECK(NULL != config, "config pointer is invalid", ESP_ERR_INVALID_ARG);
esp_err_t ret = ESP_OK;
cam_obj = (cam_obj_t *)heap_caps_calloc(1, sizeof(cam_obj_t), MALLOC_CAP_DMA);
CAM_CHECK(NULL != cam_obj, "lcd_cam object malloc error", ESP_ERR_NO_MEM);
cam_obj->swap_data = 0;
cam_obj->vsync_pin = config->pin_vsync;
cam_obj->vsync_invert = true;
ll_cam_set_pin(cam_obj, config);
ret = ll_cam_config(cam_obj, config);
CAM_CHECK_GOTO(ret == ESP_OK, "ll_cam initialize failed", err);
#if CAMERA_DBG_PIN_ENABLE
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[DBG_PIN_NUM], PIN_FUNC_GPIO);
gpio_set_direction(DBG_PIN_NUM, GPIO_MODE_OUTPUT);
gpio_set_pull_mode(DBG_PIN_NUM, GPIO_FLOATING);
#endif
ESP_LOGI(TAG, "cam init ok");
return ESP_OK;
err:
free(cam_obj);
cam_obj = NULL;
return ESP_FAIL;
}
esp_err_t cam_config(const camera_config_t *config, framesize_t frame_size, uint8_t sensor_pid)
{
CAM_CHECK(NULL != config, "config pointer is invalid", ESP_ERR_INVALID_ARG);
esp_err_t ret = ESP_OK;
ret = ll_cam_set_sample_mode(cam_obj, (pixformat_t)config->pixel_format, config->xclk_freq_hz, sensor_pid);
cam_obj->jpeg_mode = config->pixel_format == PIXFORMAT_JPEG;
#if CONFIG_IDF_TARGET_ESP32
cam_obj->psram_mode = false;
#else
cam_obj->psram_mode = (config->xclk_freq_hz == 16000000);
#endif
cam_obj->frame_cnt = config->fb_count;
cam_obj->width = resolution[frame_size].width;
cam_obj->height = resolution[frame_size].height;
if(cam_obj->jpeg_mode){
cam_obj->recv_size = cam_obj->width * cam_obj->height / 5;
cam_obj->fb_size = cam_obj->recv_size;
} else {
cam_obj->recv_size = cam_obj->width * cam_obj->height * cam_obj->in_bytes_per_pixel;
cam_obj->fb_size = cam_obj->width * cam_obj->height * cam_obj->fb_bytes_per_pixel;
}
ret = cam_dma_config();
CAM_CHECK_GOTO(ret == ESP_OK, "cam_dma_config failed", err);
cam_obj->event_queue = xQueueCreate(cam_obj->dma_half_buffer_cnt - 1, sizeof(cam_event_t));
CAM_CHECK_GOTO(cam_obj->event_queue != NULL, "event_queue create failed", err);
size_t frame_buffer_queue_len = cam_obj->frame_cnt;
if (config->grab_mode == CAMERA_GRAB_LATEST && cam_obj->frame_cnt > 1) {
frame_buffer_queue_len = cam_obj->frame_cnt - 1;
}
cam_obj->frame_buffer_queue = xQueueCreate(frame_buffer_queue_len, sizeof(camera_fb_t*));
CAM_CHECK_GOTO(cam_obj->frame_buffer_queue != NULL, "frame_buffer_queue create failed", err);
ret = ll_cam_init_isr(cam_obj);
CAM_CHECK_GOTO(ret == ESP_OK, "cam intr alloc failed", err);
#if CONFIG_CAMERA_CORE0
xTaskCreatePinnedToCore(cam_task, "cam_task", 2048, NULL, configMAX_PRIORITIES - 2, &cam_obj->task_handle, 0);
#elif CONFIG_CAMERA_CORE1
xTaskCreatePinnedToCore(cam_task, "cam_task", 2048, NULL, configMAX_PRIORITIES - 2, &cam_obj->task_handle, 1);
#else
xTaskCreate(cam_task, "cam_task", 2048, NULL, configMAX_PRIORITIES - 2, &cam_obj->task_handle);
#endif
ESP_LOGI(TAG, "cam config ok");
return ESP_OK;
err:
cam_deinit();
return ESP_FAIL;
}
esp_err_t cam_deinit(void)
{
if (!cam_obj) {
return ESP_FAIL;
}
cam_stop();
gpio_isr_handler_remove(cam_obj->vsync_pin);
if (cam_obj->task_handle) {
vTaskDelete(cam_obj->task_handle);
}
if (cam_obj->event_queue) {
vQueueDelete(cam_obj->event_queue);
}
if (cam_obj->frame_buffer_queue) {
vQueueDelete(cam_obj->frame_buffer_queue);
}
if (cam_obj->dma) {
free(cam_obj->dma);
}
if (cam_obj->dma_buffer) {
free(cam_obj->dma_buffer);
}
if (cam_obj->frames) {
for (int x = 0; x < cam_obj->frame_cnt; x++) {
free(cam_obj->frames[x].fb.buf - cam_obj->frames[x].fb_offset);
if (cam_obj->frames[x].dma) {
free(cam_obj->frames[x].dma);
}
}
free(cam_obj->frames);
}
if (cam_obj->cam_intr_handle) {
esp_intr_free(cam_obj->cam_intr_handle);
}
free(cam_obj);
cam_obj = NULL;
return ESP_OK;
}
void cam_stop(void)
{
ll_cam_vsync_intr_enable(cam_obj, false);
ll_cam_stop(cam_obj);
}
void cam_start(void)
{
ll_cam_vsync_intr_enable(cam_obj, true);
}
camera_fb_t *cam_take(TickType_t timeout)
{
camera_fb_t *dma_buffer = NULL;
TickType_t start = xTaskGetTickCount();
xQueueReceive(cam_obj->frame_buffer_queue, (void *)&dma_buffer, timeout);
if (dma_buffer) {
if(cam_obj->jpeg_mode){
// find the end marker for JPEG. Data after that can be discarded
int offset_e = cam_verify_jpeg_eoi(dma_buffer->buf, dma_buffer->len);
if (offset_e >= 0) {
// adjust buffer length
dma_buffer->len = offset_e + sizeof(JPEG_EOI_MARKER);
return dma_buffer;
} else {
ESP_LOGW(TAG, "NO-EOI");
cam_give(dma_buffer);
return cam_take(timeout - (xTaskGetTickCount() - start));//recurse!!!!
}
} else if(cam_obj->psram_mode && cam_obj->in_bytes_per_pixel != cam_obj->fb_bytes_per_pixel){
//currently this is used only for YUV to GRAYSCALE
dma_buffer->len = ll_cam_memcpy(cam_obj, dma_buffer->buf, dma_buffer->buf, dma_buffer->len);
}
return dma_buffer;
} else {
ESP_LOGI(TAG, "Failed to get the frame on time!");
}
return NULL;
}
void cam_give(camera_fb_t *dma_buffer)
{
for (int x = 0; x < cam_obj->frame_cnt; x++) {
if (&cam_obj->frames[x].fb == dma_buffer) {
cam_obj->frames[x].en = 1;
break;
}
}
}

@ -0,0 +1,60 @@
// Copyright 2010-2020 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.
#pragma once
#include "esp_camera.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Uninitialize the lcd_cam module
*
* @param handle Provide handle pointer to release resources
*
* @return
* - ESP_OK Success
* - ESP_FAIL Uninitialize fail
*/
esp_err_t cam_deinit(void);
/**
* @brief Initialize the lcd_cam module
*
* @param config Configurations - see lcd_cam_config_t struct
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
* - ESP_ERR_NO_MEM No memory to initialize lcd_cam
* - ESP_FAIL Initialize fail
*/
esp_err_t cam_init(const camera_config_t *config);
esp_err_t cam_config(const camera_config_t *config, framesize_t frame_size, uint8_t sensor_pid);
void cam_stop(void);
void cam_start(void);
camera_fb_t *cam_take(TickType_t timeout);
void cam_give(camera_fb_t *dma_buffer);
#ifdef __cplusplus
}
#endif

File diff suppressed because it is too large Load Diff

@ -15,6 +15,10 @@
#if ESP_IDF_VERSION_MAJOR >= 4 // IDF 4+
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
#include "esp32/rom/lldesc.h"
#elif CONFIG_IDF_TARGET_ESP32S2 // ESP32-S2
#include "esp32s2/rom/lldesc.h"
#elif CONFIG_IDF_TARGET_ESP32S3 // ESP32-S3
#include "esp32s3/rom/lldesc.h"
#else
#error Target CONFIG_IDF_TARGET is not supported
#endif
@ -22,28 +26,3 @@
#include "rom/lldesc.h"
#endif
typedef union {
struct {
uint8_t sample2;
uint8_t unused2;
uint8_t sample1;
uint8_t unused1;
};
uint32_t val;
} dma_elem_t;
typedef enum {
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 s2, 00 s2 00 s3, 00 s3 00 s4, ...
*/
SM_0A0B_0B0C = 0,
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 s2, 00 s3 00 s4, ...
*/
SM_0A0B_0C0D = 1,
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 00, 00 s2 00 00, 00 s3 00 00, ...
*/
SM_0A00_0B00 = 3,
} i2s_sampling_mode_t;

@ -0,0 +1,4 @@
COMPONENT_ADD_INCLUDEDIRS := driver/include conversions/include
COMPONENT_PRIV_INCLUDEDIRS := driver/private_include conversions/private_include sensors/private_include target/private_include
COMPONENT_SRCDIRS := driver conversions sensors target target/esp32
CXXFLAGS += -fno-rtti

@ -463,8 +463,9 @@ void setup()
// .frame_size = FRAMESIZE_QVGA,
// .frame_size = FRAMESIZE_UXGA,
// .frame_size = FRAMESIZE_SVGA,
.frame_size = FRAMESIZE_XGA,
// .frame_size = FRAMESIZE_VGA,
.frame_size = FRAMESIZE_UXGA,
// .frame_size = FRAMESIZE_UXGA,
.jpeg_quality = 16,
.fb_count = 2
};
@ -482,7 +483,7 @@ void setup()
sensor_t* s = esp_camera_sensor_get();
s->set_vflip(s, true);
// Configure and connect to WiFi
IPAddress ip;
@ -506,7 +507,7 @@ void setup()
xTaskCreatePinnedToCore(
mjpegCB,
"mjpeg",
2*1024,
2 * 1024,
NULL,
2,
&tMjpeg,

@ -0,0 +1,430 @@
// 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.
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include "time.h"
#include "sys/time.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "driver/gpio.h"
#include "esp_system.h"
#include "nvs_flash.h"
#include "nvs.h"
#include "sensor.h"
#include "sccb.h"
#include "cam_hal.h"
#include "esp_camera.h"
// #include "camera_common.h"
#include "xclk.h"
#if CONFIG_OV2640_SUPPORT
#include "ov2640.h"
#endif
#if CONFIG_OV7725_SUPPORT
#include "ov7725.h"
#endif
#if CONFIG_OV3660_SUPPORT
#include "ov3660.h"
#endif
#if CONFIG_OV5640_SUPPORT
#include "ov5640.h"
#endif
#if CONFIG_NT99141_SUPPORT
#include "nt99141.h"
#endif
#if CONFIG_OV7670_SUPPORT
#include "ov7670.h"
#endif
#if defined(ARDUINO_ARCH_ESP32) && defined(CONFIG_ARDUHAL_ESP_LOG)
#include "esp32-hal-log.h"
#define TAG ""
#else
#include "esp_log.h"
static const char *TAG = "camera";
#endif
typedef struct {
sensor_t sensor;
camera_fb_t fb;
} camera_state_t;
static const char* CAMERA_SENSOR_NVS_KEY = "sensor";
static const char* CAMERA_PIXFORMAT_NVS_KEY = "pixformat";
static camera_state_t *s_state = NULL;
#if CONFIG_IDF_TARGET_ESP32S3 // LCD_CAM module of ESP32-S3 will generate xclk
#define CAMERA_ENABLE_OUT_CLOCK(v)
#define CAMERA_DISABLE_OUT_CLOCK()
#else
#define CAMERA_ENABLE_OUT_CLOCK(v) camera_enable_out_clock((v))
#define CAMERA_DISABLE_OUT_CLOCK() camera_disable_out_clock()
#endif
static esp_err_t camera_probe(const camera_config_t *config, camera_model_t *out_camera_model)
{
*out_camera_model = CAMERA_NONE;
if (s_state != NULL) {
return ESP_ERR_INVALID_STATE;
}
s_state = (camera_state_t *) calloc(sizeof(camera_state_t), 1);
if (!s_state) {
return ESP_ERR_NO_MEM;
}
if (config->pin_xclk >= 0) {
ESP_LOGD(TAG, "Enabling XCLK output");
CAMERA_ENABLE_OUT_CLOCK(config);
}
if (config->pin_sscb_sda != -1) {
ESP_LOGD(TAG, "Initializing SSCB");
SCCB_Init(config->pin_sscb_sda, config->pin_sscb_scl);
}
if (config->pin_pwdn >= 0) {
ESP_LOGD(TAG, "Resetting camera by power down line");
gpio_config_t conf = { 0 };
conf.pin_bit_mask = 1LL << config->pin_pwdn;
conf.mode = GPIO_MODE_OUTPUT;
gpio_config(&conf);
// carefull, logic is inverted compared to reset pin
gpio_set_level(config->pin_pwdn, 1);
vTaskDelay(10 / portTICK_PERIOD_MS);
gpio_set_level(config->pin_pwdn, 0);
vTaskDelay(10 / portTICK_PERIOD_MS);
}
if (config->pin_reset >= 0) {
ESP_LOGD(TAG, "Resetting camera");
gpio_config_t conf = { 0 };
conf.pin_bit_mask = 1LL << config->pin_reset;
conf.mode = GPIO_MODE_OUTPUT;
gpio_config(&conf);
gpio_set_level(config->pin_reset, 0);
vTaskDelay(10 / portTICK_PERIOD_MS);
gpio_set_level(config->pin_reset, 1);
vTaskDelay(10 / portTICK_PERIOD_MS);
}
ESP_LOGD(TAG, "Searching for camera address");
vTaskDelay(10 / portTICK_PERIOD_MS);
uint8_t slv_addr = SCCB_Probe();
if (slv_addr == 0) {
CAMERA_DISABLE_OUT_CLOCK();
return ESP_ERR_NOT_FOUND;
}
ESP_LOGI(TAG, "Detected camera at address=0x%02x", slv_addr);
s_state->sensor.slv_addr = slv_addr;
s_state->sensor.xclk_freq_hz = config->xclk_freq_hz;
/**
* Read sensor ID
*/
sensor_id_t *id = &s_state->sensor.id;
if (slv_addr == OV2640_SCCB_ADDR || slv_addr == OV7725_SCCB_ADDR) {
SCCB_Write(slv_addr, 0xFF, 0x01);//bank sensor
id->PID = SCCB_Read(slv_addr, REG_PID);
id->VER = SCCB_Read(slv_addr, REG_VER);
id->MIDL = SCCB_Read(slv_addr, REG_MIDL);
id->MIDH = SCCB_Read(slv_addr, REG_MIDH);
} else if (slv_addr == OV5640_SCCB_ADDR || slv_addr == OV3660_SCCB_ADDR) {
id->PID = SCCB_Read16(slv_addr, REG16_CHIDH);
id->VER = SCCB_Read16(slv_addr, REG16_CHIDL);
} else if (slv_addr == NT99141_SCCB_ADDR) {
SCCB_Write16(slv_addr, 0x3008, 0x01);//bank sensor
id->PID = SCCB_Read16(slv_addr, 0x3000);
id->VER = SCCB_Read16(slv_addr, 0x3001);
if (config->xclk_freq_hz > 10000000) {
ESP_LOGE(TAG, "NT99141: only XCLK under 10MHz is supported, and XCLK is now set to 10M");
s_state->sensor.xclk_freq_hz = 10000000;
}
}
vTaskDelay(10 / portTICK_PERIOD_MS);
ESP_LOGI(TAG, "Camera PID=0x%02x VER=0x%02x MIDL=0x%02x MIDH=0x%02x",
id->PID, id->VER, id->MIDH, id->MIDL);
/**
* Initialize sensor according to sensor ID
*/
switch (id->PID) {
#if CONFIG_OV2640_SUPPORT
case OV2640_PID:
*out_camera_model = CAMERA_OV2640;
ov2640_init(&s_state->sensor);
break;
#endif
#if CONFIG_OV7725_SUPPORT
case OV7725_PID:
*out_camera_model = CAMERA_OV7725;
ov7725_init(&s_state->sensor);
break;
#endif
#if CONFIG_OV3660_SUPPORT
case OV3660_PID:
*out_camera_model = CAMERA_OV3660;
ov3660_init(&s_state->sensor);
break;
#endif
#if CONFIG_OV5640_SUPPORT
case OV5640_PID:
*out_camera_model = CAMERA_OV5640;
ov5640_init(&s_state->sensor);
break;
#endif
#if CONFIG_OV7670_SUPPORT
case OV7670_PID:
*out_camera_model = CAMERA_OV7670;
ov7670_init(&s_state->sensor);
break;
#endif
#if CONFIG_NT99141_SUPPORT
case NT99141_PID:
*out_camera_model = CAMERA_NT99141;
NT99141_init(&s_state->sensor);
break;
#endif
default:
id->PID = 0;
CAMERA_DISABLE_OUT_CLOCK();
ESP_LOGE(TAG, "Detected camera not supported.");
return ESP_ERR_NOT_SUPPORTED;
}
ESP_LOGD(TAG, "Doing SW reset of sensor");
s_state->sensor.reset(&s_state->sensor);
return ESP_OK;
}
esp_err_t esp_camera_init(const camera_config_t *config)
{
esp_err_t err;
err = cam_init(config);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Camera init failed with error 0x%x", err);
return err;
}
camera_model_t camera_model = CAMERA_NONE;
err = camera_probe(config, &camera_model);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Camera probe failed with error 0x%x(%s)", err, esp_err_to_name(err));
goto fail;
}
if (camera_model == CAMERA_OV7725) {
ESP_LOGI(TAG, "Detected OV7725 camera");
} else if (camera_model == CAMERA_OV2640) {
ESP_LOGI(TAG, "Detected OV2640 camera");
} else if (camera_model == CAMERA_OV3660) {
ESP_LOGI(TAG, "Detected OV3660 camera");
} else if (camera_model == CAMERA_OV5640) {
ESP_LOGI(TAG, "Detected OV5640 camera");
} else if (camera_model == CAMERA_OV7670) {
ESP_LOGI(TAG, "Detected OV7670 camera");
} else if (camera_model == CAMERA_NT99141) {
ESP_LOGI(TAG, "Detected NT99141 camera");
} else {
ESP_LOGI(TAG, "Camera not supported");
err = ESP_ERR_CAMERA_NOT_SUPPORTED;
goto fail;
}
framesize_t frame_size = (framesize_t) config->frame_size;
pixformat_t pix_format = (pixformat_t) config->pixel_format;
if (frame_size > camera_sensor[camera_model].max_size) {
frame_size = camera_sensor[camera_model].max_size;
}
err = cam_config(config, frame_size, s_state->sensor.id.PID);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Camera config failed with error 0x%x", err);
goto fail;
}
s_state->sensor.status.framesize = frame_size;
s_state->sensor.pixformat = pix_format;
// ESP_LOGD(TAG, "Setting frame size to %dx%d", s_state->width, s_state->height);
if (s_state->sensor.set_framesize(&s_state->sensor, frame_size) != 0) {
ESP_LOGE(TAG, "Failed to set frame size");
err = ESP_ERR_CAMERA_FAILED_TO_SET_FRAME_SIZE;
goto fail;
}
s_state->sensor.set_pixformat(&s_state->sensor, pix_format);
if (s_state->sensor.id.PID == OV2640_PID) {
s_state->sensor.set_gainceiling(&s_state->sensor, GAINCEILING_2X);
s_state->sensor.set_bpc(&s_state->sensor, false);
s_state->sensor.set_wpc(&s_state->sensor, true);
s_state->sensor.set_lenc(&s_state->sensor, true);
}
if (pix_format == PIXFORMAT_JPEG) {
(*s_state->sensor.set_quality)(&s_state->sensor, config->jpeg_quality);
}
s_state->sensor.init_status(&s_state->sensor);
cam_start();
return ESP_OK;
fail:
CAMERA_DISABLE_OUT_CLOCK();
return err;
}
esp_err_t esp_camera_deinit()
{
esp_err_t ret = cam_deinit();
if (s_state) {
SCCB_Deinit();
free(s_state);
s_state = NULL;
}
return ret;
}
#define FB_GET_TIMEOUT (4000 / portTICK_PERIOD_MS)
camera_fb_t *esp_camera_fb_get()
{
if (s_state == NULL) {
return NULL;
}
camera_fb_t *fb = cam_take(FB_GET_TIMEOUT);
//set the frame properties
if (fb) {
fb->width = resolution[s_state->sensor.status.framesize].width;
fb->height = resolution[s_state->sensor.status.framesize].height;
fb->format = s_state->sensor.pixformat;
}
return fb;
}
void esp_camera_fb_return(camera_fb_t *fb)
{
if (s_state == NULL) {
return;
}
cam_give(fb);
}
sensor_t *esp_camera_sensor_get()
{
if (s_state == NULL) {
return NULL;
}
return &s_state->sensor;
}
esp_err_t esp_camera_save_to_nvs(const char *key)
{
#if ESP_IDF_VERSION_MAJOR > 3
nvs_handle_t handle;
#else
nvs_handle handle;
#endif
esp_err_t ret = nvs_open(key,NVS_READWRITE,&handle);
if (ret == ESP_OK) {
sensor_t *s = esp_camera_sensor_get();
if (s != NULL) {
ret = nvs_set_blob(handle,CAMERA_SENSOR_NVS_KEY,&s->status,sizeof(camera_status_t));
if (ret == ESP_OK) {
uint8_t pf = s->pixformat;
ret = nvs_set_u8(handle,CAMERA_PIXFORMAT_NVS_KEY,pf);
}
return ret;
} else {
return ESP_ERR_CAMERA_NOT_DETECTED;
}
nvs_close(handle);
return ret;
} else {
return ret;
}
}
esp_err_t esp_camera_load_from_nvs(const char *key)
{
#if ESP_IDF_VERSION_MAJOR > 3
nvs_handle_t handle;
#else
nvs_handle handle;
#endif
uint8_t pf;
esp_err_t ret = nvs_open(key,NVS_READWRITE,&handle);
if (ret == ESP_OK) {
sensor_t *s = esp_camera_sensor_get();
camera_status_t st;
if (s != NULL) {
size_t size = sizeof(camera_status_t);
ret = nvs_get_blob(handle,CAMERA_SENSOR_NVS_KEY,&st,&size);
if (ret == ESP_OK) {
s->set_ae_level(s,st.ae_level);
s->set_aec2(s,st.aec2);
s->set_aec_value(s,st.aec_value);
s->set_agc_gain(s,st.agc_gain);
s->set_awb_gain(s,st.awb_gain);
s->set_bpc(s,st.bpc);
s->set_brightness(s,st.brightness);
s->set_colorbar(s,st.colorbar);
s->set_contrast(s,st.contrast);
s->set_dcw(s,st.dcw);
s->set_denoise(s,st.denoise);
s->set_exposure_ctrl(s,st.aec);
s->set_framesize(s,st.framesize);
s->set_gain_ctrl(s,st.agc);
s->set_gainceiling(s,st.gainceiling);
s->set_hmirror(s,st.hmirror);
s->set_lenc(s,st.lenc);
s->set_quality(s,st.quality);
s->set_raw_gma(s,st.raw_gma);
s->set_saturation(s,st.saturation);
s->set_sharpness(s,st.sharpness);
s->set_special_effect(s,st.special_effect);
s->set_vflip(s,st.vflip);
s->set_wb_mode(s,st.wb_mode);
s->set_whitebal(s,st.awb);
s->set_wpc(s,st.wpc);
}
ret = nvs_get_u8(handle,CAMERA_PIXFORMAT_NVS_KEY,&pf);
if (ret == ESP_OK) {
s->set_pixformat(s,pf);
}
} else {
return ESP_ERR_CAMERA_NOT_DETECTED;
}
nvs_close(handle);
return ret;
} else {
ESP_LOGW(TAG,"Error (%d) opening nvs key \"%s\"",ret,key);
return ret;
}
}

@ -38,7 +38,8 @@
.pixel_format = PIXFORMAT_JPEG,
.frame_size = FRAMESIZE_SVGA,
.jpeg_quality = 10,
.fb_count = 2
.fb_count = 2,
.grab_mode = CAMERA_GRAB_WHEN_EMPTY
};
esp_err_t camera_example_init(){
@ -74,6 +75,14 @@
extern "C" {
#endif
/**
* @brief Configuration structure for camera initialization
*/
typedef enum {
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 */
} camera_grab_mode_t;
/**
* @brief Configuration structure for camera initialization
*/
@ -95,7 +104,7 @@ typedef struct {
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) */
int xclk_freq_hz; /*!< Frequency of XCLK signal, in Hz. EXPERIMENTAL: Set to 16MHz on ESP32-S2 or ESP32-S3 to enable EDMA mode */
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 */
@ -105,6 +114,7 @@ typedef struct {
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_grab_mode_t grab_mode; /*!< When buffers should be filled */
} camera_config_t;
/**

@ -17,7 +17,11 @@
#if ESP_IDF_VERSION_MAJOR >= 4 // IDF 4+
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
#include "esp32/rom/tjpgd.h"
#else
#elif CONFIG_IDF_TARGET_ESP32S2
#include "tjpgd.h"
#elif CONFIG_IDF_TARGET_ESP32S3
#include "esp32s3/rom/tjpgd.h"
#else
#error Target CONFIG_IDF_TARGET is not supported
#endif
#else // ESP32 Before IDF 4.0

@ -22,6 +22,7 @@ extern "C" {
#include <stdint.h>
#include <stdbool.h>
#include "esp_camera.h"
#include "esp_jpg_decode.h"
typedef size_t (* jpg_out_cb)(void * arg, size_t index, const void* data, size_t len);
@ -120,6 +121,8 @@ bool frame2bmp(camera_fb_t * fb, uint8_t ** out, size_t * out_len);
*/
bool fmt2rgb888(const uint8_t *src_buf, size_t src_len, pixformat_t format, uint8_t * rgb_buf);
bool jpg2rgb565(const uint8_t *src, size_t src_len, uint8_t * out, jpg_scale_t scale);
#ifdef __cplusplus
}
#endif

@ -0,0 +1,26 @@
{
"name": "esp32-camera",
"version": "1.0.0",
"keywords": "esp32, camera, espressif, esp32-cam",
"description": "ESP32 compatible driver for OV2640, OV3660, OV5640, OV7670 and OV7725 image sensors.",
"repository": {
"type": "git",
"url": "https://github.com/espressif/esp32-camera"
},
"frameworks": "espidf",
"platforms": "*",
"build": {
"flags": [
"-Idriver/include",
"-Iconversions/include",
"-Idriver/private_include",
"-Iconversions/private_include",
"-Isensors/private_include",
"-Itarget/private_include",
"-fno-rtti"
],
"includeDir": ".",
"srcDir": ".",
"srcFilter": ["-<*>", "+<driver>", "+<conversions>", "+<sensors>"]
}
}

@ -0,0 +1,515 @@
// Copyright 2010-2020 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.
#include <stdio.h>
#include <string.h>
#include "soc/i2s_struct.h"
#include "esp_idf_version.h"
#if ESP_IDF_VERSION_MAJOR >= 4
#include "hal/gpio_ll.h"
#else
#include "rom/ets_sys.h"
#include "soc/gpio_periph.h"
#define esp_rom_delay_us ets_delay_us
static inline int gpio_ll_get_level(gpio_dev_t *hw, int gpio_num)
{
if (gpio_num < 32) {
return (hw->in >> gpio_num) & 0x1;
} else {
return (hw->in1.data >> (gpio_num - 32)) & 0x1;
}
}
#endif
#include "ll_cam.h"
#include "xclk.h"
#include "cam_hal.h"
static const char *TAG = "esp32 ll_cam";
#define I2S_ISR_ENABLE(i) {I2S0.int_clr.i = 1;I2S0.int_ena.i = 1;}
#define I2S_ISR_DISABLE(i) {I2S0.int_ena.i = 0;I2S0.int_clr.i = 1;}
typedef union {
struct {
uint32_t sample2:8;
uint32_t unused2:8;
uint32_t sample1:8;
uint32_t unused1:8;
};
uint32_t val;
} dma_elem_t;
typedef enum {
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 s2, 00 s2 00 s3, 00 s3 00 s4, ...
*/
SM_0A0B_0B0C = 0,
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 s2, 00 s3 00 s4, ...
*/
SM_0A0B_0C0D = 1,
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 00, 00 s2 00 00, 00 s3 00 00, ...
*/
SM_0A00_0B00 = 3,
} i2s_sampling_mode_t;
typedef size_t (*dma_filter_t)(uint8_t* dst, const uint8_t* src, size_t len);
static i2s_sampling_mode_t sampling_mode = SM_0A00_0B00;
static size_t ll_cam_bytes_per_sample(i2s_sampling_mode_t mode)
{
switch(mode) {
case SM_0A00_0B00:
return 4;
case SM_0A0B_0B0C:
return 4;
case SM_0A0B_0C0D:
return 2;
default:
assert(0 && "invalid sampling mode");
return 0;
}
}
static size_t IRAM_ATTR ll_cam_dma_filter_jpeg(uint8_t* dst, const uint8_t* src, size_t len)
{
const dma_elem_t* dma_el = (const dma_elem_t*)src;
size_t elements = len / sizeof(dma_elem_t);
size_t end = elements / 4;
// manually unrolling 4 iterations of the loop here
for (size_t i = 0; i < end; ++i) {
dst[0] = dma_el[0].sample1;
dst[1] = dma_el[1].sample1;
dst[2] = dma_el[2].sample1;
dst[3] = dma_el[3].sample1;
dma_el += 4;
dst += 4;
}
return elements;
}
static size_t IRAM_ATTR ll_cam_dma_filter_grayscale(uint8_t* dst, const uint8_t* src, size_t len)
{
const dma_elem_t* dma_el = (const dma_elem_t*)src;
size_t elements = len / sizeof(dma_elem_t);
size_t end = elements / 4;
for (size_t i = 0; i < end; ++i) {
// manually unrolling 4 iterations of the loop here
dst[0] = dma_el[0].sample1;
dst[1] = dma_el[1].sample1;
dst[2] = dma_el[2].sample1;
dst[3] = dma_el[3].sample1;
dma_el += 4;
dst += 4;
}
return elements;
}
static size_t IRAM_ATTR ll_cam_dma_filter_grayscale_highspeed(uint8_t* dst, const uint8_t* src, size_t len)
{
const dma_elem_t* dma_el = (const dma_elem_t*)src;
size_t elements = len / sizeof(dma_elem_t);
size_t end = elements / 8;
for (size_t i = 0; i < end; ++i) {
// manually unrolling 4 iterations of the loop here
dst[0] = dma_el[0].sample1;
dst[1] = dma_el[2].sample1;
dst[2] = dma_el[4].sample1;
dst[3] = dma_el[6].sample1;
dma_el += 8;
dst += 4;
}
// the final sample of a line in SM_0A0B_0B0C sampling mode needs special handling
if ((elements & 0x7) != 0) {
dst[0] = dma_el[0].sample1;
dst[1] = dma_el[2].sample1;
elements += 1;
}
return elements / 2;
}
static size_t IRAM_ATTR ll_cam_dma_filter_yuyv(uint8_t* dst, const uint8_t* src, size_t len)
{
const dma_elem_t* dma_el = (const dma_elem_t*)src;
size_t elements = len / sizeof(dma_elem_t);
size_t end = elements / 4;
for (size_t i = 0; i < end; ++i) {
dst[0] = dma_el[0].sample1;//y0
dst[1] = dma_el[0].sample2;//u
dst[2] = dma_el[1].sample1;//y1
dst[3] = dma_el[1].sample2;//v
dst[4] = dma_el[2].sample1;//y0
dst[5] = dma_el[2].sample2;//u
dst[6] = dma_el[3].sample1;//y1
dst[7] = dma_el[3].sample2;//v
dma_el += 4;
dst += 8;
}
return elements * 2;
}
static size_t IRAM_ATTR ll_cam_dma_filter_yuyv_highspeed(uint8_t* dst, const uint8_t* src, size_t len)
{
const dma_elem_t* dma_el = (const dma_elem_t*)src;
size_t elements = len / sizeof(dma_elem_t);
size_t end = elements / 8;
for (size_t i = 0; i < end; ++i) {
dst[0] = dma_el[0].sample1;//y0
dst[1] = dma_el[1].sample1;//u
dst[2] = dma_el[2].sample1;//y1
dst[3] = dma_el[3].sample1;//v
dst[4] = dma_el[4].sample1;//y0
dst[5] = dma_el[5].sample1;//u
dst[6] = dma_el[6].sample1;//y1
dst[7] = dma_el[7].sample1;//v
dma_el += 8;
dst += 8;
}
if ((elements & 0x7) != 0) {
dst[0] = dma_el[0].sample1;//y0
dst[1] = dma_el[1].sample1;//u
dst[2] = dma_el[2].sample1;//y1
dst[3] = dma_el[2].sample2;//v
elements += 4;
}
return elements;
}
static void IRAM_ATTR ll_cam_vsync_isr(void *arg)
{
//DBG_PIN_SET(1);
cam_obj_t *cam = (cam_obj_t *)arg;
BaseType_t HPTaskAwoken = pdFALSE;
// filter
esp_rom_delay_us(1);
if (gpio_ll_get_level(&GPIO, cam->vsync_pin) == !cam->vsync_invert) {
ll_cam_send_event(cam, CAM_VSYNC_EVENT, &HPTaskAwoken);
if (HPTaskAwoken == pdTRUE) {
portYIELD_FROM_ISR();
}
}
//DBG_PIN_SET(0);
}
static void IRAM_ATTR ll_cam_dma_isr(void *arg)
{
//DBG_PIN_SET(1);
cam_obj_t *cam = (cam_obj_t *)arg;
BaseType_t HPTaskAwoken = pdFALSE;
typeof(I2S0.int_st) status = I2S0.int_st;
if (status.val == 0) {
return;
}
I2S0.int_clr.val = status.val;
if (status.in_suc_eof) {
ll_cam_send_event(cam, CAM_IN_SUC_EOF_EVENT, &HPTaskAwoken);
}
if (HPTaskAwoken == pdTRUE) {
portYIELD_FROM_ISR();
}
//DBG_PIN_SET(0);
}
bool ll_cam_stop(cam_obj_t *cam)
{
I2S0.conf.rx_start = 0;
I2S_ISR_DISABLE(in_suc_eof);
I2S0.in_link.stop = 1;
return true;
}
bool ll_cam_start(cam_obj_t *cam, int frame_pos)
{
I2S0.conf.rx_start = 0;
I2S_ISR_ENABLE(in_suc_eof);
I2S0.conf.rx_reset = 1;
I2S0.conf.rx_reset = 0;
I2S0.conf.rx_fifo_reset = 1;
I2S0.conf.rx_fifo_reset = 0;
I2S0.lc_conf.in_rst = 1;
I2S0.lc_conf.in_rst = 0;
I2S0.lc_conf.ahbm_fifo_rst = 1;
I2S0.lc_conf.ahbm_fifo_rst = 0;
I2S0.lc_conf.ahbm_rst = 1;
I2S0.lc_conf.ahbm_rst = 0;
I2S0.rx_eof_num = cam->dma_half_buffer_size / sizeof(dma_elem_t);
I2S0.in_link.addr = ((uint32_t)&cam->dma[0]) & 0xfffff;
I2S0.in_link.start = 1;
I2S0.conf.rx_start = 1;
return true;
}
esp_err_t ll_cam_config(cam_obj_t *cam, const camera_config_t *config)
{
// Enable and configure I2S peripheral
periph_module_enable(PERIPH_I2S0_MODULE);
I2S0.conf.rx_reset = 1;
I2S0.conf.rx_reset = 0;
I2S0.conf.rx_fifo_reset = 1;
I2S0.conf.rx_fifo_reset = 0;
I2S0.lc_conf.in_rst = 1;
I2S0.lc_conf.in_rst = 0;
I2S0.lc_conf.ahbm_fifo_rst = 1;
I2S0.lc_conf.ahbm_fifo_rst = 0;
I2S0.lc_conf.ahbm_rst = 1;
I2S0.lc_conf.ahbm_rst = 0;
I2S0.conf.rx_slave_mod = 1;
I2S0.conf.rx_right_first = 0;
I2S0.conf.rx_msb_right = 0;
I2S0.conf.rx_msb_shift = 0;
I2S0.conf.rx_mono = 0;
I2S0.conf.rx_short_sync = 0;
I2S0.conf2.lcd_en = 1;
I2S0.conf2.camera_en = 1;
// Configure clock divider
I2S0.clkm_conf.clkm_div_a = 0;
I2S0.clkm_conf.clkm_div_b = 0;
I2S0.clkm_conf.clkm_div_num = 2;
I2S0.fifo_conf.dscr_en = 1;
I2S0.fifo_conf.rx_fifo_mod = sampling_mode;
I2S0.fifo_conf.rx_fifo_mod_force_en = 1;
I2S0.conf_chan.rx_chan_mod = 1;
I2S0.sample_rate_conf.rx_bits_mod = 0;
I2S0.timing.val = 0;
I2S0.timing.rx_dsync_sw = 1;
return ESP_OK;
}
void ll_cam_vsync_intr_enable(cam_obj_t *cam, bool en)
{
if (en) {
gpio_intr_enable(cam->vsync_pin);
} else {
gpio_intr_disable(cam->vsync_pin);
}
}
esp_err_t ll_cam_set_pin(cam_obj_t *cam, const camera_config_t *config)
{
gpio_config_t io_conf = {0};
io_conf.intr_type = cam->vsync_invert ? GPIO_PIN_INTR_NEGEDGE : GPIO_PIN_INTR_POSEDGE;
io_conf.pin_bit_mask = 1ULL << config->pin_vsync;
io_conf.mode = GPIO_MODE_INPUT;
io_conf.pull_up_en = 1;
io_conf.pull_down_en = 0;
gpio_config(&io_conf);
gpio_install_isr_service(ESP_INTR_FLAG_LOWMED | ESP_INTR_FLAG_IRAM);
gpio_isr_handler_add(config->pin_vsync, ll_cam_vsync_isr, cam);
gpio_intr_disable(config->pin_vsync);
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[config->pin_pclk], PIN_FUNC_GPIO);
gpio_set_direction(config->pin_pclk, GPIO_MODE_INPUT);
gpio_set_pull_mode(config->pin_pclk, GPIO_FLOATING);
gpio_matrix_in(config->pin_pclk, I2S0I_WS_IN_IDX, false);
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[config->pin_vsync], PIN_FUNC_GPIO);
gpio_set_direction(config->pin_vsync, GPIO_MODE_INPUT);
gpio_set_pull_mode(config->pin_vsync, GPIO_FLOATING);
gpio_matrix_in(config->pin_vsync, I2S0I_V_SYNC_IDX, false);
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[config->pin_href], PIN_FUNC_GPIO);
gpio_set_direction(config->pin_href, GPIO_MODE_INPUT);
gpio_set_pull_mode(config->pin_href, GPIO_FLOATING);
gpio_matrix_in(config->pin_href, I2S0I_H_SYNC_IDX, false);
int data_pins[8] = {
config->pin_d0, config->pin_d1, config->pin_d2, config->pin_d3, config->pin_d4, config->pin_d5, config->pin_d6, config->pin_d7,
};
for (int i = 0; i < 8; i++) {
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[data_pins[i]], PIN_FUNC_GPIO);
gpio_set_direction(data_pins[i], GPIO_MODE_INPUT);
gpio_set_pull_mode(data_pins[i], GPIO_FLOATING);
gpio_matrix_in(data_pins[i], I2S0I_DATA_IN0_IDX + i, false);
}
gpio_matrix_in(0x38, I2S0I_H_ENABLE_IDX, false);
return ESP_OK;
}
esp_err_t ll_cam_init_isr(cam_obj_t *cam)
{
return esp_intr_alloc(ETS_I2S0_INTR_SOURCE, ESP_INTR_FLAG_LOWMED | ESP_INTR_FLAG_IRAM, ll_cam_dma_isr, cam, &cam->cam_intr_handle);
}
void ll_cam_do_vsync(cam_obj_t *cam)
{
}
uint8_t ll_cam_get_dma_align(cam_obj_t *cam)
{
return 0;
}
static bool ll_cam_calc_rgb_dma(cam_obj_t *cam){
size_t dma_half_buffer_max = 16 * 1024 / cam->dma_bytes_per_item;
size_t dma_buffer_max = 2 * dma_half_buffer_max;
size_t node_max = LCD_CAM_DMA_NODE_BUFFER_MAX_SIZE / cam->dma_bytes_per_item;
size_t line_width = cam->width * cam->in_bytes_per_pixel;
size_t image_size = cam->height * line_width;
if (image_size > (2 * 1024 * 1024) || (line_width > dma_half_buffer_max)) {
ESP_LOGE(TAG, "Resolution too high");
return 0;
}
size_t node_size = node_max;
size_t nodes_per_line = 1;
size_t lines_per_node = 1;
size_t lines_per_half_buffer = 1;
size_t dma_half_buffer_min = node_max;
size_t dma_half_buffer = dma_half_buffer_max;
size_t dma_buffer_size = dma_buffer_max;
// Calculate DMA Node Size so that it's divisable by or divisor of the line width
if(line_width >= node_max){
// One or more nodes will be requied for one line
for(size_t i = node_max; i > 0; i=i-1){
if ((line_width % i) == 0) {
node_size = i;
nodes_per_line = line_width / node_size;
break;
}
}
} else {
// One or more lines can fit into one node
for(size_t i = node_max; i > 0; i=i-1){
if ((i % line_width) == 0) {
node_size = i;
lines_per_node = node_size / line_width;
while((cam->height % lines_per_node) != 0){
lines_per_node = lines_per_node - 1;
node_size = lines_per_node * line_width;
}
break;
}
}
}
// Calculate minimum EOF size = max(mode_size, line_size)
dma_half_buffer_min = node_size * nodes_per_line;
// Calculate max EOF size divisable by node size
dma_half_buffer = (dma_half_buffer_max / dma_half_buffer_min) * dma_half_buffer_min;
// Adjust EOF size so that height will be divisable by the number of lines in each EOF
lines_per_half_buffer = dma_half_buffer / line_width;
while((cam->height % lines_per_half_buffer) != 0){
dma_half_buffer = dma_half_buffer - dma_half_buffer_min;
lines_per_half_buffer = dma_half_buffer / line_width;
}
// Calculate DMA size
dma_buffer_size =(dma_buffer_max / dma_half_buffer) * dma_half_buffer;
ESP_LOGI(TAG, "node_size: %4u, nodes_per_line: %u, lines_per_node: %u, dma_half_buffer_min: %5u, dma_half_buffer: %5u, lines_per_half_buffer: %2u, dma_buffer_size: %5u, image_size: %u",
node_size * cam->dma_bytes_per_item, nodes_per_line, lines_per_node, dma_half_buffer_min * cam->dma_bytes_per_item, dma_half_buffer * cam->dma_bytes_per_item, lines_per_half_buffer, dma_buffer_size * cam->dma_bytes_per_item, image_size);
cam->dma_buffer_size = dma_buffer_size * cam->dma_bytes_per_item;
cam->dma_half_buffer_size = dma_half_buffer * cam->dma_bytes_per_item;
cam->dma_node_buffer_size = node_size * cam->dma_bytes_per_item;
cam->dma_half_buffer_cnt = cam->dma_buffer_size / cam->dma_half_buffer_size;
return 1;
}
bool ll_cam_dma_sizes(cam_obj_t *cam)
{
cam->dma_bytes_per_item = ll_cam_bytes_per_sample(sampling_mode);
if (cam->jpeg_mode) {
cam->dma_half_buffer_cnt = 8;
cam->dma_node_buffer_size = 2048;
cam->dma_half_buffer_size = cam->dma_node_buffer_size * 2;
cam->dma_buffer_size = cam->dma_half_buffer_cnt * cam->dma_half_buffer_size;
} else {
return ll_cam_calc_rgb_dma(cam);
}
return 1;
}
static dma_filter_t dma_filter = ll_cam_dma_filter_jpeg;
size_t IRAM_ATTR ll_cam_memcpy(cam_obj_t *cam, uint8_t *out, const uint8_t *in, size_t len)
{
//DBG_PIN_SET(1);
size_t r = dma_filter(out, in, len);
//DBG_PIN_SET(0);
return r;
}
esp_err_t ll_cam_set_sample_mode(cam_obj_t *cam, pixformat_t pix_format, uint32_t xclk_freq_hz, uint8_t sensor_pid)
{
if (pix_format == PIXFORMAT_GRAYSCALE) {
if (sensor_pid == OV3660_PID || sensor_pid == OV5640_PID || sensor_pid == NT99141_PID) {
if (xclk_freq_hz > 10000000) {
sampling_mode = SM_0A00_0B00;
dma_filter = ll_cam_dma_filter_yuyv_highspeed;
} else {
sampling_mode = SM_0A0B_0C0D;
dma_filter = ll_cam_dma_filter_yuyv;
}
cam->in_bytes_per_pixel = 1; // camera sends Y8
} else {
if (xclk_freq_hz > 10000000 && sensor_pid != OV7725_PID) {
sampling_mode = SM_0A00_0B00;
dma_filter = ll_cam_dma_filter_grayscale_highspeed;
} else {
sampling_mode = SM_0A0B_0C0D;
dma_filter = ll_cam_dma_filter_grayscale;
}
cam->in_bytes_per_pixel = 2; // camera sends YU/YV
}
cam->fb_bytes_per_pixel = 1; // frame buffer stores Y8
} else if (pix_format == PIXFORMAT_YUV422 || pix_format == PIXFORMAT_RGB565) {
if (xclk_freq_hz > 10000000 && sensor_pid != OV7725_PID) {
if (sensor_pid == OV7670_PID) {
sampling_mode = SM_0A0B_0B0C;
} else {
sampling_mode = SM_0A00_0B00;
}
dma_filter = ll_cam_dma_filter_yuyv_highspeed;
} else {
sampling_mode = SM_0A0B_0C0D;
dma_filter = ll_cam_dma_filter_yuyv;
}
cam->in_bytes_per_pixel = 2; // camera sends YU/YV
cam->fb_bytes_per_pixel = 2; // frame buffer stores YU/YV/RGB565
} else if (pix_format == PIXFORMAT_JPEG) {
if (sensor_pid != OV2640_PID && sensor_pid != OV3660_PID && sensor_pid != OV5640_PID && sensor_pid != NT99141_PID) {
ESP_LOGE(TAG, "JPEG format is not supported on this sensor");
return ESP_ERR_NOT_SUPPORTED;
}
cam->in_bytes_per_pixel = 1;
cam->fb_bytes_per_pixel = 1;
dma_filter = ll_cam_dma_filter_jpeg;
sampling_mode = SM_0A00_0B00;
} else {
ESP_LOGE(TAG, "Requested format is not supported");
return ESP_ERR_NOT_SUPPORTED;
}
I2S0.fifo_conf.rx_fifo_mod = sampling_mode;
return ESP_OK;
}

@ -0,0 +1,136 @@
// Copyright 2010-2020 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.
#pragma once
#include <stdint.h>
#include "sdkconfig.h"
#if CONFIG_IDF_TARGET_ESP32
#if ESP_IDF_VERSION_MAJOR >= 4
#include "esp32/rom/lldesc.h"
#else
#include "rom/lldesc.h"
#endif
#elif CONFIG_IDF_TARGET_ESP32S2
#include "esp32s2/rom/lldesc.h"
#elif CONFIG_IDF_TARGET_ESP32S3
#include "esp32s3/rom/lldesc.h"
#endif
#include "esp_log.h"
#include "esp_camera.h"
#include "camera_common.h"
#include "freertos/FreeRTOS.h"
#include "freertos/queue.h"
#include "freertos/task.h"
#include "freertos/semphr.h"
#define CAMERA_DBG_PIN_ENABLE 0
#if CAMERA_DBG_PIN_ENABLE
#if CONFIG_IDF_TARGET_ESP32
#define DBG_PIN_NUM 26
#else
#define DBG_PIN_NUM 7
#endif
#include "hal/gpio_ll.h"
#define DBG_PIN_SET(v) gpio_ll_set_level(&GPIO, DBG_PIN_NUM, v)
#else
#define DBG_PIN_SET(v)
#endif
#define CAM_CHECK(a, str, ret) if (!(a)) { \
ESP_LOGE(TAG,"%s(%d): %s", __FUNCTION__, __LINE__, str); \
return (ret); \
}
#define CAM_CHECK_GOTO(a, str, lab) if (!(a)) { \
ESP_LOGE(TAG,"%s(%d): %s", __FUNCTION__, __LINE__, str); \
goto lab; \
}
#define LCD_CAM_DMA_NODE_BUFFER_MAX_SIZE (4092)
typedef enum {
CAM_IN_SUC_EOF_EVENT = 0,
CAM_VSYNC_EVENT
} cam_event_t;
typedef enum {
CAM_STATE_IDLE = 0,
CAM_STATE_READ_BUF = 1,
} cam_state_t;
typedef struct {
camera_fb_t fb;
uint8_t en;
//for RGB/YUV modes
lldesc_t *dma;
size_t fb_offset;
} cam_frame_t;
typedef struct {
uint32_t dma_bytes_per_item;
uint32_t dma_buffer_size;
uint32_t dma_half_buffer_size;
uint32_t dma_half_buffer_cnt;
uint32_t dma_node_buffer_size;
uint32_t dma_node_cnt;
uint32_t frame_copy_cnt;
//for JPEG mode
lldesc_t *dma;
uint8_t *dma_buffer;
cam_frame_t *frames;
QueueHandle_t event_queue;
QueueHandle_t frame_buffer_queue;
TaskHandle_t task_handle;
intr_handle_t cam_intr_handle;
uint8_t dma_num;//ESP32-S3
intr_handle_t dma_intr_handle;//ESP32-S3
uint8_t jpeg_mode;
uint8_t vsync_pin;
uint8_t vsync_invert;
uint32_t frame_cnt;
uint32_t recv_size;
bool swap_data;
bool psram_mode;
//for RGB/YUV modes
uint16_t width;
uint16_t height;
uint8_t in_bytes_per_pixel;
uint8_t fb_bytes_per_pixel;
uint32_t fb_size;
cam_state_t state;
} cam_obj_t;
bool ll_cam_stop(cam_obj_t *cam);
bool ll_cam_start(cam_obj_t *cam, int frame_pos);
esp_err_t ll_cam_config(cam_obj_t *cam, const camera_config_t *config);
void ll_cam_vsync_intr_enable(cam_obj_t *cam, bool en);
esp_err_t ll_cam_set_pin(cam_obj_t *cam, const camera_config_t *config);
esp_err_t ll_cam_init_isr(cam_obj_t *cam);
void ll_cam_do_vsync(cam_obj_t *cam);
uint8_t ll_cam_get_dma_align(cam_obj_t *cam);
bool ll_cam_dma_sizes(cam_obj_t *cam);
size_t ll_cam_memcpy(cam_obj_t *cam, uint8_t *out, const uint8_t *in, size_t len);
esp_err_t ll_cam_set_sample_mode(cam_obj_t *cam, pixformat_t pix_format, uint32_t xclk_freq_hz, uint8_t sensor_pid);
// implemented in cam_hal
void ll_cam_send_event(cam_obj_t *cam, cam_event_t cam_event, BaseType_t * HPTaskAwoken);

@ -144,28 +144,6 @@ static int write_addr_reg(uint8_t slv_addr, const uint16_t reg, uint16_t x_value
#define write_reg_bits(slv_addr, reg, mask, enable) set_reg_bits(slv_addr, reg, 0, mask, enable?mask:0)
static int calc_sysclk(int xclk, bool pll_bypass, int pll_multiplier, int pll_sys_div, int pll_pre_div, bool pll_root_2x, int pll_seld5, bool pclk_manual, int pclk_div)
{
const int pll_pre_div2x_map[] = { 2, 3, 4, 6 };//values are multiplied by two to avoid floats
const int pll_seld52x_map[] = { 2, 2, 4, 5 };
if (!pll_sys_div) {
pll_sys_div = 1;
}
int pll_pre_div2x = pll_pre_div2x_map[pll_pre_div];
int pll_root_div = pll_root_2x ? 2 : 1;
int pll_seld52x = pll_seld52x_map[pll_seld5];
int VCO = (xclk / 1000) * pll_multiplier * pll_root_div * 2 / pll_pre_div2x;
int PLLCLK = pll_bypass ? (xclk) : (VCO * 1000 * 2 / pll_sys_div / pll_seld52x);
int PCLK = PLLCLK / 2 / ((pclk_manual && pclk_div) ? pclk_div : 1);
int SYSCLK = PLLCLK / 4;
ESP_LOGD(TAG, "Calculated VCO: %d Hz, PLLCLK: %d Hz, SYSCLK: %d Hz, PCLK: %d Hz", VCO * 1000, PLLCLK, SYSCLK, PCLK);
return SYSCLK;
}
static int set_pll(sensor_t *sensor, bool bypass, uint8_t multiplier, uint8_t sys_div, uint8_t pre_div, bool root_2x, uint8_t seld5, bool pclk_manual, uint8_t pclk_div)
{
return -1;
@ -309,7 +287,7 @@ static int set_framesize(sensor_t *sensor, framesize_t framesize)
ret = write_regs(sensor->slv_addr, sensor_framesize_VGA);
}
return 0;
return ret;
}
static int set_hmirror(sensor_t *sensor, int enable)
@ -682,7 +660,6 @@ static int set_brightness(sensor_t *sensor, int level)
{
int ret = 0;
uint8_t value = 0;
bool negative = false;
switch (level) {
case 3:
@ -699,17 +676,14 @@ static int set_brightness(sensor_t *sensor, int level)
case -1:
value = 0x78;
negative = true;
break;
case -2:
value = 0x70;
negative = true;
break;
case -3:
value = 0x60;
negative = true;
break;
default: // 0
@ -730,7 +704,6 @@ static int set_contrast(sensor_t *sensor, int level)
{
int ret = 0;
uint8_t value1 = 0, value2 = 0 ;
bool negative = false;
switch (level) {
case 3:

@ -157,26 +157,40 @@ static int set_window(sensor_t *sensor, ov2640_sensor_mode_t mode, int offset_x,
{0, 0}
};
c.pclk_auto = 0;
c.pclk_div = 8;
c.clk_2x = 0;
c.clk_div = 0;
if(sensor->pixformat != PIXFORMAT_JPEG){
c.pclk_auto = 1;
if (sensor->pixformat == PIXFORMAT_JPEG) {
c.clk_2x = 0;
c.clk_div = 0;
c.pclk_auto = 0;
c.pclk_div = 8;
if(mode == OV2640_MODE_UXGA) {
c.pclk_div = 12;
}
// if (sensor->xclk_freq_hz == 16000000) {
// c.pclk_div = c.pclk_div / 2;
// }
} else {
#if CONFIG_IDF_TARGET_ESP32
c.clk_2x = 0;
#else
c.clk_2x = 1;
#endif
c.clk_div = 7;
c.pclk_auto = 1;
c.pclk_div = 8;
if (mode == OV2640_MODE_CIF) {
c.clk_div = 3;
} else if(mode == OV2640_MODE_UXGA) {
c.pclk_div = 12;
}
}
ESP_LOGI(TAG, "Set PLL: clk_2x: %u, clk_div: %u, pclk_auto: %u, pclk_div: %u", c.clk_2x, c.clk_div, c.pclk_auto, c.pclk_div);
if (mode == OV2640_MODE_CIF) {
regs = ov2640_settings_to_cif;
if(sensor->pixformat != PIXFORMAT_JPEG){
c.clk_div = 3;
}
} else if (mode == OV2640_MODE_SVGA) {
regs = ov2640_settings_to_svga;
} else {
regs = ov2640_settings_to_uxga;
c.pclk_div = 12;
}
WRITE_REG_OR_RETURN(BANK_DSP, R_BYPASS, R_BYPASS_DSP_BYPAS);

@ -142,7 +142,7 @@ static int calc_sysclk(int xclk, bool pll_bypass, int pll_multiplier, int pll_sy
int PCLK = PLLCLK / 2 / ((pclk_manual && pclk_div)?pclk_div:1);
int SYSCLK = PLLCLK / 4;
ESP_LOGD(TAG, "Calculated VCO: %d Hz, PLLCLK: %d Hz, SYSCLK: %d Hz, PCLK: %d Hz", VCO*1000, PLLCLK, SYSCLK, PCLK);
ESP_LOGI(TAG, "Calculated VCO: %d Hz, PLLCLK: %d Hz, SYSCLK: %d Hz, PCLK: %d Hz", VCO*1000, PLLCLK, SYSCLK, PCLK);
return SYSCLK;
}
@ -310,13 +310,13 @@ static int set_image_options(sensor_t *sensor)
static int set_framesize(sensor_t *sensor, framesize_t framesize)
{
int ret = 0;
framesize_t old_framesize = sensor->status.framesize;
sensor->status.framesize = framesize;
if(framesize > FRAMESIZE_QXGA){
ESP_LOGE(TAG, "Invalid framesize: %u", framesize);
return -1;
ESP_LOGW(TAG, "Invalid framesize: %u", framesize);
framesize = FRAMESIZE_QXGA;
}
framesize_t old_framesize = sensor->status.framesize;
sensor->status.framesize = framesize;
uint16_t w = resolution[framesize].width;
uint16_t h = resolution[framesize].height;
aspect_ratio_t ratio = resolution[sensor->status.framesize].aspect_ratio;
@ -355,7 +355,7 @@ static int set_framesize(sensor_t *sensor, framesize_t framesize)
}
if (sensor->pixformat == PIXFORMAT_JPEG) {
if (framesize == FRAMESIZE_QXGA) {
if (framesize == FRAMESIZE_QXGA || sensor->xclk_freq_hz == 16000000) {
//40MHz SYSCLK and 10MHz PCLK
ret = set_pll(sensor, false, 24, 1, 3, false, 0, true, 8);
} else {
@ -363,12 +363,16 @@ static int set_framesize(sensor_t *sensor, framesize_t framesize)
ret = set_pll(sensor, false, 30, 1, 3, false, 0, true, 10);
}
} else {
if (framesize > FRAMESIZE_CIF) {
//10MHz SYSCLK and 10MHz PCLK (6.19 FPS)
ret = set_pll(sensor, false, 2, 1, 0, false, 0, true, 2);
//tuned for 16MHz XCLK and 8MHz PCLK
if (framesize > FRAMESIZE_HVGA) {
//8MHz SYSCLK and 8MHz PCLK (4.44 FPS)
ret = set_pll(sensor, false, 4, 1, 0, false, 2, true, 2);
} else if (framesize >= FRAMESIZE_QVGA) {
//16MHz SYSCLK and 8MHz PCLK (10.25 FPS)
ret = set_pll(sensor, false, 8, 1, 0, false, 2, true, 4);
} else {
//25MHz SYSCLK and 10MHz PCLK (15.45 FPS)
ret = set_pll(sensor, false, 5, 1, 0, false, 0, true, 5);
//32MHz SYSCLK and 8MHz PCLK (17.77 FPS)
ret = set_pll(sensor, false, 8, 1, 0, false, 0, true, 8);
}
}

@ -196,7 +196,7 @@ static int calc_sysclk(int xclk, bool pll_bypass, int pll_multiplier, int pll_sy
unsigned int SYSCLK = PLL_CLK / 4;
ESP_LOGD(TAG, "Calculated XVCLK: %d Hz, REFIN: %u Hz, VCO: %u Hz, PLL_CLK: %u Hz, SYSCLK: %u Hz, PCLK: %u Hz", xclk, REFIN, VCO, PLL_CLK, SYSCLK, PCLK);
ESP_LOGI(TAG, "Calculated XVCLK: %d Hz, REFIN: %u Hz, VCO: %u Hz, PLL_CLK: %u Hz, SYSCLK: %u Hz, PCLK: %u Hz", xclk, REFIN, VCO, PLL_CLK, SYSCLK, PCLK);
return SYSCLK;
}
@ -209,6 +209,7 @@ static int set_pll(sensor_t *sensor, bool bypass, uint8_t multiplier, uint8_t sy
if(multiplier > 127){
multiplier &= 0xFE;//only even integers above 127
}
ESP_LOGI(TAG, "Set PLL: bypass: %u, multiplier: %u, sys_div: %u, pre_div: %u, root_2x: %u, pclk_root_div: %u, pclk_manual: %u, pclk_div: %u", bypass, multiplier, sys_div, pre_div, root_2x, pclk_root_div, pclk_manual, pclk_div);
calc_sysclk(sensor->xclk_freq_hz, bypass, multiplier, sys_div, pre_div, root_2x, pclk_root_div, pclk_manual, pclk_div);
@ -432,14 +433,22 @@ static int set_framesize(sensor_t *sensor, framesize_t framesize)
if (sensor->pixformat == PIXFORMAT_JPEG) {
//10MHz PCLK
uint8_t sys_mul = 200;
if(framesize < FRAMESIZE_QVGA){
if(framesize < FRAMESIZE_QVGA || sensor->xclk_freq_hz == 16000000){
sys_mul = 160;
} else if(framesize < FRAMESIZE_XGA){
sys_mul = 180;
}
ret = set_pll(sensor, false, sys_mul, 4, 2, false, 2, true, 4);
//Set PLL: bypass: 0, multiplier: sys_mul, sys_div: 4, pre_div: 2, root_2x: 0, pclk_root_div: 2, pclk_manual: 1, pclk_div: 4
} else {
ret = set_pll(sensor, false, 10, 1, 1, false, 1, true, 4);
//ret = set_pll(sensor, false, 8, 1, 1, false, 1, true, 4);
if (framesize > FRAMESIZE_HVGA) {
ret = set_pll(sensor, false, 10, 1, 2, false, 1, true, 2);
} else if (framesize >= FRAMESIZE_QVGA) {
ret = set_pll(sensor, false, 8, 1, 1, false, 1, true, 4);
} else {
ret = set_pll(sensor, false, 20, 1, 1, false, 1, true, 8);
}
}
if (ret == 0) {

@ -11,6 +11,7 @@
#include <freertos/FreeRTOS.h>
#include <freertos/task.h>
#include "sccb.h"
#include "sensor.h"
#include <stdio.h>
#include "sdkconfig.h"
#if defined(ARDUINO_ARCH_ESP32) && defined(CONFIG_ARDUHAL_ESP_LOG)
@ -36,12 +37,10 @@ const int SCCB_I2C_PORT = 1;
#else
const int SCCB_I2C_PORT = 0;
#endif
static uint8_t ESP_SLAVE_ADDR = 0x3c;
int SCCB_Init(int pin_sda, int pin_scl)
{
ESP_LOGI(TAG, "pin_sda %d pin_scl %d\n", pin_sda, pin_scl);
//log_i("SCCB_Init start");
ESP_LOGI(TAG, "pin_sda %d pin_scl %d", pin_sda, pin_scl);
i2c_config_t conf;
memset(&conf, 0, sizeof(i2c_config_t));
conf.mode = I2C_MODE_MASTER;
@ -56,10 +55,30 @@ int SCCB_Init(int pin_sda, int pin_scl)
return 0;
}
uint8_t SCCB_Probe()
int SCCB_Deinit(void)
{
return i2c_driver_delete(SCCB_I2C_PORT);
}
uint8_t SCCB_Probe(void)
{
uint8_t slave_addr = 0x0;
while(slave_addr < 0x7f) {
// for (size_t i = 1; i < 0x80; i++) {
// i2c_cmd_handle_t cmd = i2c_cmd_link_create();
// i2c_master_start(cmd);
// i2c_master_write_byte(cmd, ( i << 1 ) | WRITE_BIT, ACK_CHECK_EN);
// i2c_master_stop(cmd);
// esp_err_t ret = i2c_master_cmd_begin(SCCB_I2C_PORT, cmd, 1000 / portTICK_RATE_MS);
// i2c_cmd_link_delete(cmd);
// if( ret == ESP_OK) {
// ESP_LOGW(TAG, "Found I2C Device at 0x%02X", i);
// }
// }
for (size_t i = 0; i < CAMERA_MODEL_MAX; i++) {
if (slave_addr == camera_sensor[i].sccb_addr) {
continue;
}
slave_addr = camera_sensor[i].sccb_addr;
i2c_cmd_handle_t cmd = i2c_cmd_link_create();
i2c_master_start(cmd);
i2c_master_write_byte(cmd, ( slave_addr << 1 ) | WRITE_BIT, ACK_CHECK_EN);
@ -67,12 +86,10 @@ uint8_t SCCB_Probe()
esp_err_t ret = i2c_master_cmd_begin(SCCB_I2C_PORT, cmd, 1000 / portTICK_RATE_MS);
i2c_cmd_link_delete(cmd);
if( ret == ESP_OK) {
ESP_SLAVE_ADDR = slave_addr;
return ESP_SLAVE_ADDR;
return slave_addr;
}
slave_addr++;
}
return ESP_SLAVE_ADDR;
return 0;
}
uint8_t SCCB_Read(uint8_t slv_addr, uint8_t reg)

@ -10,6 +10,7 @@
#define __SCCB_H__
#include <stdint.h>
int SCCB_Init(int pin_sda, int pin_scl);
int SCCB_Deinit(void);
uint8_t SCCB_Probe();
uint8_t SCCB_Read(uint8_t slv_addr, uint8_t reg);
uint8_t SCCB_Write(uint8_t slv_addr, uint8_t reg, uint8_t data);

@ -1,5 +1,14 @@
#include "sensor.h"
const camera_sensor_info_t camera_sensor[CAMERA_MODEL_MAX] = {
{CAMERA_OV7725, OV7725_SCCB_ADDR, OV7725_PID, FRAMESIZE_VGA},
{CAMERA_OV2640, OV2640_SCCB_ADDR, OV2640_PID, FRAMESIZE_UXGA},
{CAMERA_OV3660, OV3660_SCCB_ADDR, OV3660_PID, FRAMESIZE_QXGA},
{CAMERA_OV5640, OV5640_SCCB_ADDR, OV5640_PID, FRAMESIZE_QSXGA},
{CAMERA_OV7670, OV7670_SCCB_ADDR, OV7670_PID, FRAMESIZE_VGA},
{CAMERA_NT99141, NT99141_SCCB_ADDR, NT99141_PID, FRAMESIZE_HD},
};
const resolution_info_t resolution[FRAMESIZE_INVALID] = {
{ 96, 96, ASPECT_RATIO_1X1 }, /* 96x96 */
{ 160, 120, ASPECT_RATIO_4X3 }, /* QQVGA */

@ -11,13 +11,45 @@
#include <stdint.h>
#include <stdbool.h>
#define NT99141_PID (0x14)
#define OV9650_PID (0x96)
#define OV7725_PID (0x77)
#define OV2640_PID (0x26)
#define OV3660_PID (0x36)
#define OV5640_PID (0x56)
#define OV7670_PID (0x76)
// Chip ID Registers
#define REG_PID 0x0A
#define REG_VER 0x0B
#define REG_MIDH 0x1C
#define REG_MIDL 0x1D
#define REG16_CHIDH 0x300A
#define REG16_CHIDL 0x300B
typedef enum {
OV9650_PID = 0x96,
OV7725_PID = 0x77,
OV2640_PID = 0x26,
OV3660_PID = 0x36,
OV5640_PID = 0x56,
OV7670_PID = 0x76,
NT99141_PID = 0x14
} camera_pid_t;
typedef enum {
CAMERA_OV7725,
CAMERA_OV2640,
CAMERA_OV3660,
CAMERA_OV5640,
CAMERA_OV7670,
CAMERA_NT99141,
CAMERA_MODEL_MAX,
CAMERA_NONE,
CAMERA_UNKNOWN
} camera_model_t;
typedef enum {
OV2640_SCCB_ADDR = 0x30,
OV5640_SCCB_ADDR = 0x3C,
OV3660_SCCB_ADDR = 0x3C,
OV7725_SCCB_ADDR = 0x21,
OV7670_SCCB_ADDR = 0x21,
NT99141_SCCB_ADDR = 0x2A,
} camera_sccb_addr_t;
typedef enum {
PIXFORMAT_RGB565, // 2BPP/RGB565
@ -58,6 +90,13 @@ typedef enum {
FRAMESIZE_INVALID
} framesize_t;
typedef struct {
const camera_model_t model;
const camera_sccb_addr_t sccb_addr;
const camera_pid_t pid;
const framesize_t max_size;
} camera_sensor_info_t;
typedef enum {
ASPECT_RATIO_4X3,
ASPECT_RATIO_3X2,
@ -101,6 +140,8 @@ typedef struct {
// Resolution table (in sensor.c)
extern const resolution_info_t resolution[];
// camera sensor table (in sensor.c)
extern const camera_sensor_info_t camera_sensor[];
typedef struct {
uint8_t MIDH;

@ -24,6 +24,10 @@
#if ESP_IDF_VERSION_MAJOR >= 4 // IDF 4+
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
#include "esp32/spiram.h"
#elif CONFIG_IDF_TARGET_ESP32S2
#include "esp32s2/spiram.h"
#elif CONFIG_IDF_TARGET_ESP32S3
#include "esp32s3/spiram.h"
#else
#error Target CONFIG_IDF_TARGET is not supported
#endif
@ -115,6 +119,54 @@ static bool _rgb_write(void * arg, uint16_t x, uint16_t y, uint16_t w, uint16_t
return true;
}
static bool _rgb565_write(void * arg, uint16_t x, uint16_t y, uint16_t w, uint16_t h, uint8_t *data)
{
rgb_jpg_decoder * jpeg = (rgb_jpg_decoder *)arg;
if(!data){
if(x == 0 && y == 0){
//write start
jpeg->width = w;
jpeg->height = h;
//if output is null, this is BMP
if(!jpeg->output){
jpeg->output = (uint8_t *)_malloc((w*h*3)+jpeg->data_offset);
if(!jpeg->output){
return false;
}
}
} else {
//write end
}
return true;
}
size_t jw = jpeg->width*3;
size_t jw2 = jpeg->width*2;
size_t t = y * jw;
size_t t2 = y * jw2;
size_t b = t + (h * jw);
size_t l = x * 2;
uint8_t *out = jpeg->output+jpeg->data_offset;
uint8_t *o = out;
size_t iy, iy2, ix, ix2;
w = w * 3;
for(iy=t, iy2=t2; iy<b; iy+=jw, iy2+=jw2) {
o = out+iy2+l;
for(ix2=ix=0; ix<w; ix+= 3, ix2 +=2) {
uint16_t r = data[ix];
uint16_t g = data[ix+1];
uint16_t b = data[ix+2];
uint16_t c = ((r & 0xF8) << 8) | ((g & 0xFC) << 3) | (b >> 3);
o[ix2+1] = c>>8;
o[ix2] = c&0xff;
}
data+=w;
}
return true;
}
//input buffer
static uint32_t _jpg_read(void * arg, size_t index, uint8_t *buf, size_t len)
{
@ -140,6 +192,21 @@ static bool jpg2rgb888(const uint8_t *src, size_t src_len, uint8_t * out, jpg_sc
return true;
}
bool jpg2rgb565(const uint8_t *src, size_t src_len, uint8_t * out, jpg_scale_t scale)
{
rgb_jpg_decoder jpeg;
jpeg.width = 0;
jpeg.height = 0;
jpeg.input = src;
jpeg.output = out;
jpeg.data_offset = 0;
if(esp_jpg_decode(src_len, scale, _jpg_read, _rgb565_write, (void*)&jpeg) != ESP_OK){
return false;
}
return true;
}
bool jpg2bmp(const uint8_t *src, size_t src_len, uint8_t ** out, size_t * out_len)
{

@ -25,6 +25,10 @@
#if ESP_IDF_VERSION_MAJOR >= 4 // IDF 4+
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
#include "esp32/spiram.h"
#elif CONFIG_IDF_TARGET_ESP32S2
#include "esp32s2/spiram.h"
#elif CONFIG_IDF_TARGET_ESP32S3
#include "esp32s3/spiram.h"
#else
#error Target CONFIG_IDF_TARGET is not supported
#endif
@ -195,7 +199,7 @@ public:
return true;
}
if ((size_t)len > (max_len - index)) {
ESP_LOGW(TAG, "JPG output overflow: %d bytes", len - (max_len - index));
//ESP_LOGW(TAG, "JPG output overflow: %d bytes (%d,%d,%d)", len - (max_len - index), len, index, max_len);
len = max_len - index;
}
if (len) {
@ -215,7 +219,7 @@ bool fmt2jpg(uint8_t *src, size_t src_len, uint16_t width, uint16_t height, pixf
{
//todo: allocate proper buffer for holding JPEG data
//this should be enough for CIF frame size
int jpg_buf_len = 64*1024;
int jpg_buf_len = 128*1024;
uint8_t * jpg_buf = (uint8_t *)_malloc(jpg_buf_len);

@ -1,432 +0,0 @@
/*
si2c.c - Software I2C library for ESP31B
Copyright (c) 2015 Hristo Gochkov. All rights reserved.
This file is part of the ESP31B core for Arduino environment.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include <stdint.h>
#include <stdbool.h>
#include "twi.h"
#include "soc/gpio_reg.h"
#include "soc/gpio_struct.h"
#include "soc/io_mux_reg.h"
#include "driver/rtc_io.h"
#include <stdio.h>
#define LOW 0x0
#define HIGH 0x1
//GPIO FUNCTIONS
#define INPUT 0x01
#define OUTPUT 0x02
#define PULLUP 0x04
#define INPUT_PULLUP 0x05
#define PULLDOWN 0x08
#define INPUT_PULLDOWN 0x09
#define OPEN_DRAIN 0x10
#define OUTPUT_OPEN_DRAIN 0x12
#define SPECIAL 0xF0
#define FUNCTION_1 0x00
#define FUNCTION_2 0x20
#define FUNCTION_3 0x40
#define FUNCTION_4 0x60
#define FUNCTION_5 0x80
#define FUNCTION_6 0xA0
#define ESP_REG(addr) *((volatile uint32_t *)(addr))
const uint8_t pin_to_mux[40] = { 0x44, 0x88, 0x40, 0x84, 0x48, 0x6c, 0x60, 0x64, 0x68, 0x54, 0x58, 0x5c, 0x34, 0x38, 0x30, 0x3c, 0x4c, 0x50, 0x70, 0x74, 0x78, 0x7c, 0x80, 0x8c, 0, 0x24, 0x28, 0x2c, 0, 0, 0, 0, 0x1c, 0x20, 0x14, 0x18, 0x04, 0x08, 0x0c, 0x10};
static void pinMode(uint8_t pin, uint8_t mode)
{
if(pin >= 40) {
return;
}
uint32_t rtc_reg = rtc_gpio_desc[pin].reg;
//RTC pins PULL settings
if(rtc_reg) {
//lock rtc
ESP_REG(rtc_reg) = ESP_REG(rtc_reg) & ~(rtc_gpio_desc[pin].mux);
if(mode & PULLUP) {
ESP_REG(rtc_reg) = (ESP_REG(rtc_reg) | rtc_gpio_desc[pin].pullup) & ~(rtc_gpio_desc[pin].pulldown);
} else if(mode & PULLDOWN) {
ESP_REG(rtc_reg) = (ESP_REG(rtc_reg) | rtc_gpio_desc[pin].pulldown) & ~(rtc_gpio_desc[pin].pullup);
} else {
ESP_REG(rtc_reg) = ESP_REG(rtc_reg) & ~(rtc_gpio_desc[pin].pullup | rtc_gpio_desc[pin].pulldown);
}
//unlock rtc
}
uint32_t pinFunction = 0, pinControl = 0;
//lock gpio
if(mode & INPUT) {
if(pin < 32) {
GPIO.enable_w1tc = BIT(pin);
} else {
GPIO.enable1_w1tc.val = BIT(pin - 32);
}
} else if(mode & OUTPUT) {
if(pin > 33) {
//unlock gpio
return;//pins above 33 can be only inputs
} else if(pin < 32) {
GPIO.enable_w1ts = BIT(pin);
} else {
GPIO.enable1_w1ts.val = BIT(pin - 32);
}
}
if(mode & PULLUP) {
pinFunction |= FUN_PU;
} else if(mode & PULLDOWN) {
pinFunction |= FUN_PD;
}
pinFunction |= ((uint32_t)2 << FUN_DRV_S);//what are the drivers?
pinFunction |= FUN_IE;//input enable but required for output as well?
if(mode & (INPUT | OUTPUT)) {
pinFunction |= ((uint32_t)2 << MCU_SEL_S);
} else if(mode == SPECIAL) {
pinFunction |= ((uint32_t)(((pin)==1||(pin)==3)?0:1) << MCU_SEL_S);
} else {
pinFunction |= ((uint32_t)(mode >> 5) << MCU_SEL_S);
}
ESP_REG(DR_REG_IO_MUX_BASE + pin_to_mux[pin]) = pinFunction;
if(mode & OPEN_DRAIN) {
pinControl = (1 << GPIO_PIN0_PAD_DRIVER_S);
}
GPIO.pin[pin].val = pinControl;
//unlock gpio
}
static void digitalWrite(uint8_t pin, uint8_t val)
{
if(val) {
if(pin < 32) {
GPIO.out_w1ts = BIT(pin);
} else if(pin < 34) {
GPIO.out1_w1ts.val = BIT(pin - 32);
}
} else {
if(pin < 32) {
GPIO.out_w1tc = BIT(pin);
} else if(pin < 34) {
GPIO.out1_w1tc.val = BIT(pin - 32);
}
}
}
unsigned char twi_dcount = 18;
static unsigned char twi_sda, twi_scl;
static inline void SDA_LOW()
{
//Enable SDA (becomes output and since GPO is 0 for the pin,
// it will pull the line low)
if (twi_sda < 32) {
GPIO.enable_w1ts = BIT(twi_sda);
} else {
GPIO.enable1_w1ts.val = BIT(twi_sda - 32);
}
}
static inline void SDA_HIGH()
{
//Disable SDA (becomes input and since it has pullup it will go high)
if (twi_sda < 32) {
GPIO.enable_w1tc = BIT(twi_sda);
} else {
GPIO.enable1_w1tc.val = BIT(twi_sda - 32);
}
}
static inline uint32_t SDA_READ()
{
if (twi_sda < 32) {
return (GPIO.in & BIT(twi_sda)) != 0;
} else {
return (GPIO.in1.val & BIT(twi_sda - 32)) != 0;
}
}
static void SCL_LOW()
{
if (twi_scl < 32) {
GPIO.enable_w1ts = BIT(twi_scl);
} else {
GPIO.enable1_w1ts.val = BIT(twi_scl - 32);
}
}
static void SCL_HIGH()
{
if (twi_scl < 32) {
GPIO.enable_w1tc = BIT(twi_scl);
} else {
GPIO.enable1_w1tc.val = BIT(twi_scl - 32);
}
}
static uint32_t SCL_READ()
{
if (twi_scl < 32) {
return (GPIO.in & BIT(twi_scl)) != 0;
} else {
return (GPIO.in1.val & BIT(twi_scl - 32)) != 0;
}
}
#ifndef FCPU80
#define FCPU80 80000000L
#endif
#if F_CPU == FCPU80
#define TWI_CLOCK_STRETCH 800
#else
#define TWI_CLOCK_STRETCH 1600
#endif
void twi_setClock(unsigned int freq)
{
#if F_CPU == FCPU80
if(freq <= 100000) {
twi_dcount = 19; //about 100KHz
} else if(freq <= 200000) {
twi_dcount = 8; //about 200KHz
} else if(freq <= 300000) {
twi_dcount = 3; //about 300KHz
} else if(freq <= 400000) {
twi_dcount = 1; //about 400KHz
} else {
twi_dcount = 1; //about 400KHz
}
#else
if(freq <= 100000) {
twi_dcount = 32; //about 100KHz
} else if(freq <= 200000) {
twi_dcount = 14; //about 200KHz
} else if(freq <= 300000) {
twi_dcount = 8; //about 300KHz
} else if(freq <= 400000) {
twi_dcount = 5; //about 400KHz
} else if(freq <= 500000) {
twi_dcount = 3; //about 500KHz
} else if(freq <= 600000) {
twi_dcount = 2; //about 600KHz
} else {
twi_dcount = 1; //about 700KHz
}
#endif
}
void twi_init(unsigned char sda, unsigned char scl)
{
twi_sda = sda;
twi_scl = scl;
pinMode(twi_sda, OUTPUT);
pinMode(twi_scl, OUTPUT);
digitalWrite(twi_sda, 0);
digitalWrite(twi_scl, 0);
pinMode(twi_sda, INPUT_PULLUP);
pinMode(twi_scl, INPUT_PULLUP);
twi_setClock(100000);
}
void twi_stop(void)
{
pinMode(twi_sda, INPUT);
pinMode(twi_scl, INPUT);
}
static void twi_delay(unsigned char v)
{
unsigned int i;
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-but-set-variable"
unsigned int reg;
for(i=0; i<v; i++) {
reg = REG_READ(GPIO_IN_REG);
}
#pragma GCC diagnostic pop
}
static bool twi_write_start(void)
{
SCL_HIGH();
SDA_HIGH();
if (SDA_READ() == 0) {
return false;
}
twi_delay(twi_dcount);
SDA_LOW();
twi_delay(twi_dcount);
return true;
}
static bool twi_write_stop(void)
{
unsigned int i = 0;
SCL_LOW();
SDA_LOW();
twi_delay(twi_dcount);
SCL_HIGH();
while (SCL_READ() == 0 && (i++) < TWI_CLOCK_STRETCH);// Clock stretching (up to 100us)
twi_delay(twi_dcount);
SDA_HIGH();
twi_delay(twi_dcount);
return true;
}
bool do_log = false;
static bool twi_write_bit(bool bit)
{
unsigned int i = 0;
SCL_LOW();
if (bit) {
SDA_HIGH();
if (do_log) {
twi_delay(twi_dcount+1);
}
} else {
SDA_LOW();
if (do_log) {}
}
twi_delay(twi_dcount+1);
SCL_HIGH();
while (SCL_READ() == 0 && (i++) < TWI_CLOCK_STRETCH);// Clock stretching (up to 100us)
twi_delay(twi_dcount);
return true;
}
static bool twi_read_bit(void)
{
unsigned int i = 0;
SCL_LOW();
SDA_HIGH();
twi_delay(twi_dcount+2);
SCL_HIGH();
while (SCL_READ() == 0 && (i++) < TWI_CLOCK_STRETCH);// Clock stretching (up to 100us)
bool bit = SDA_READ();
twi_delay(twi_dcount);
return bit;
}
static bool twi_write_byte(unsigned char byte)
{
if (byte == 0x43) {
// printf("TWB %02x ", (uint32_t) byte);
// do_log = true;
}
unsigned char bit;
for (bit = 0; bit < 8; bit++) {
twi_write_bit((byte & 0x80) != 0);
byte <<= 1;
}
if (do_log) {
printf("\n");
do_log = false;
}
return !twi_read_bit();//NACK/ACK
}
static unsigned char twi_read_byte(bool nack)
{
unsigned char byte = 0;
unsigned char bit;
for (bit = 0; bit < 8; bit++) {
byte = (byte << 1) | twi_read_bit();
}
twi_write_bit(nack);
return byte;
}
unsigned char twi_writeTo(unsigned char address, unsigned char * buf, unsigned int len, unsigned char sendStop)
{
unsigned int i;
if(!twi_write_start()) {
return 4; //line busy
}
if(!twi_write_byte(((address << 1) | 0) & 0xFF)) {
if (sendStop) {
twi_write_stop();
}
return 2; //received NACK on transmit of address
}
for(i=0; i<len; i++) {
if(!twi_write_byte(buf[i])) {
if (sendStop) {
twi_write_stop();
}
return 3;//received NACK on transmit of data
}
}
if(sendStop) {
twi_write_stop();
}
i = 0;
while(SDA_READ() == 0 && (i++) < 10) {
SCL_LOW();
twi_delay(twi_dcount);
SCL_HIGH();
twi_delay(twi_dcount);
}
return 0;
}
unsigned char twi_readFrom(unsigned char address, unsigned char* buf, unsigned int len, unsigned char sendStop)
{
unsigned int i;
if(!twi_write_start()) {
return 4; //line busy
}
if(!twi_write_byte(((address << 1) | 1) & 0xFF)) {
if (sendStop) {
twi_write_stop();
}
return 2;//received NACK on transmit of address
}
for(i=0; i<(len-1); i++) {
buf[i] = twi_read_byte(false);
}
buf[len-1] = twi_read_byte(true);
if(sendStop) {
twi_write_stop();
}
i = 0;
while(SDA_READ() == 0 && (i++) < 10) {
SCL_LOW();
twi_delay(twi_dcount);
SCL_HIGH();
twi_delay(twi_dcount);
}
return 0;
}

@ -1,38 +0,0 @@
/*
twi.h - Software I2C library for ESP31B
Copyright (c) 2015 Hristo Gochkov. All rights reserved.
This file is part of the ESP31B core for Arduino environment.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifndef SI2C_h
#define SI2C_h
#ifdef __cplusplus
extern "C" {
#endif
void twi_init(unsigned char sda, unsigned char scl);
void twi_stop(void);
void twi_setClock(unsigned int freq);
uint8_t twi_writeTo(unsigned char address, unsigned char * buf, unsigned int len, unsigned char sendStop);
uint8_t twi_readFrom(unsigned char address, unsigned char * buf, unsigned int len, unsigned char sendStop);
#ifdef __cplusplus
}
#endif
#endif

@ -15,9 +15,13 @@ static const char* TAG = "camera_xclk";
esp_err_t xclk_timer_conf(int ledc_timer, int xclk_freq_hz)
{
ledc_timer_config_t timer_conf;
timer_conf.duty_resolution = 2;
timer_conf.duty_resolution = LEDC_TIMER_1_BIT;
timer_conf.freq_hz = xclk_freq_hz;
#if CONFIG_IDF_TARGET_ESP32
timer_conf.speed_mode = LEDC_HIGH_SPEED_MODE;
#else
timer_conf.speed_mode = LEDC_LOW_SPEED_MODE;
#endif
#if ESP_IDF_VERSION_MAJOR >= 4
timer_conf.clk_cfg = LEDC_AUTO_CLK;
#endif
@ -41,11 +45,15 @@ esp_err_t camera_enable_out_clock(camera_config_t* config)
ledc_channel_config_t ch_conf;
ch_conf.gpio_num = config->pin_xclk;
#if CONFIG_IDF_TARGET_ESP32
ch_conf.speed_mode = LEDC_HIGH_SPEED_MODE;
#else
ch_conf.speed_mode = LEDC_LOW_SPEED_MODE;
#endif
ch_conf.channel = config->ledc_channel;
ch_conf.intr_type = LEDC_INTR_DISABLE;
ch_conf.timer_sel = config->ledc_timer;
ch_conf.duty = 2;
ch_conf.duty = 1;
ch_conf.hpoint = 0;
err = ledc_channel_config(&ch_conf);
if (err != ESP_OK) {

@ -0,0 +1 @@
*.DS_Store

@ -0,0 +1,61 @@
if(IDF_TARGET STREQUAL "esp32" OR IDF_TARGET STREQUAL "esp32s2" OR IDF_TARGET STREQUAL "esp32s3")
set(COMPONENT_SRCS
driver/esp_camera.c
driver/cam_hal.c
driver/sccb.c
driver/sensor.c
sensors/ov2640.c
sensors/ov3660.c
sensors/ov5640.c
sensors/ov7725.c
sensors/ov7670.c
sensors/nt99141.c
conversions/yuv.c
conversions/to_jpg.cpp
conversions/to_bmp.c
conversions/jpge.cpp
conversions/esp_jpg_decode.c
)
set(COMPONENT_ADD_INCLUDEDIRS
driver/include
conversions/include
)
set(COMPONENT_PRIV_INCLUDEDIRS
driver/private_include
sensors/private_include
conversions/private_include
target/private_include
)
if(IDF_TARGET STREQUAL "esp32")
list(APPEND COMPONENT_SRCS
target/xclk.c
target/esp32/ll_cam.c
)
endif()
if(IDF_TARGET STREQUAL "esp32s2")
list(APPEND COMPONENT_SRCS
target/xclk.c
target/esp32s2/ll_cam.c
target/esp32s2/tjpgd.c
)
list(APPEND COMPONENT_PRIV_INCLUDEDIRS
target/esp32s2/private_include
)
endif()
if(IDF_TARGET STREQUAL "esp32s3")
list(APPEND COMPONENT_SRCS
target/esp32s3/ll_cam.c
)
endif()
set(COMPONENT_REQUIRES driver)
set(COMPONENT_PRIV_REQUIRES freertos nvs_flash)
register_component()
endif()

@ -0,0 +1,71 @@
menu "Camera configuration"
config OV7670_SUPPORT
bool "Support OV7670 VGA"
default y
help
Enable this option if you want to use the OV7670.
Disable this option to save memory.
config OV7725_SUPPORT
bool "Support OV7725 SVGA"
default n
help
Enable this option if you want to use the OV7725.
Disable this option to save memory.
config NT99141_SUPPORT
bool "Support NT99141 HD"
default y
help
Enable this option if you want to use the NT99141.
Disable this option to save memory.
config OV2640_SUPPORT
bool "Support OV2640 2MP"
default y
help
Enable this option if you want to use the OV2640.
Disable this option to save memory.
config OV3660_SUPPORT
bool "Support OV3660 3MP"
default y
help
Enable this option if you want to use the OV3360.
Disable this option to save memory.
config OV5640_SUPPORT
bool "Support OV5640 5MP"
default y
help
Enable this option if you want to use the OV5640.
Disable this option to save memory.
choice SCCB_HARDWARE_I2C_PORT
bool "I2C peripheral to use for SCCB"
default SCCB_HARDWARE_I2C_PORT1
config SCCB_HARDWARE_I2C_PORT0
bool "I2C0"
config SCCB_HARDWARE_I2C_PORT1
bool "I2C1"
endchoice
choice CAMERA_TASK_PINNED_TO_CORE
bool "Camera task pinned to core"
default CAMERA_CORE0
help
Pin the camera handle task to a certain core(0/1). It can also be done automatically choosing NO_AFFINITY.
config CAMERA_CORE0
bool "CORE0"
config CAMERA_CORE1
bool "CORE1"
config CAMERA_NO_AFFINITY
bool "NO_AFFINITY"
endchoice
endmenu

@ -0,0 +1,202 @@
Apache License
Version 2.0, January 2004
http://www.apache.org/licenses/
TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
1. Definitions.
"License" shall mean the terms and conditions for use, reproduction,
and distribution as defined by Sections 1 through 9 of this document.
"Licensor" shall mean the copyright owner or entity authorized by
the copyright owner that is granting the License.
"Legal Entity" shall mean the union of the acting entity and all
other entities that control, are controlled by, or are under common
control with that entity. For the purposes of this definition,
"control" means (i) the power, direct or indirect, to cause the
direction or management of such entity, whether by contract or
otherwise, or (ii) ownership of fifty percent (50%) or more of the
outstanding shares, or (iii) beneficial ownership of such entity.
"You" (or "Your") shall mean an individual or Legal Entity
exercising permissions granted by this License.
"Source" form shall mean the preferred form for making modifications,
including but not limited to software source code, documentation
source, and configuration files.
"Object" form shall mean any form resulting from mechanical
transformation or translation of a Source form, including but
not limited to compiled object code, generated documentation,
and conversions to other media types.
"Work" shall mean the work of authorship, whether in Source or
Object form, made available under the License, as indicated by a
copyright notice that is included in or attached to the work
(an example is provided in the Appendix below).
"Derivative Works" shall mean any work, whether in Source or Object
form, that is based on (or derived from) the Work and for which the
editorial revisions, annotations, elaborations, or other modifications
represent, as a whole, an original work of authorship. For the purposes
of this License, Derivative Works shall not include works that remain
separable from, or merely link (or bind by name) to the interfaces of,
the Work and Derivative Works thereof.
"Contribution" shall mean any work of authorship, including
the original version of the Work and any modifications or additions
to that Work or Derivative Works thereof, that is intentionally
submitted to Licensor for inclusion in the Work by the copyright owner
or by an individual or Legal Entity authorized to submit on behalf of
the copyright owner. For the purposes of this definition, "submitted"
means any form of electronic, verbal, or written communication sent
to the Licensor or its representatives, including but not limited to
communication on electronic mailing lists, source code control systems,
and issue tracking systems that are managed by, or on behalf of, the
Licensor for the purpose of discussing and improving the Work, but
excluding communication that is conspicuously marked or otherwise
designated in writing by the copyright owner as "Not a Contribution."
"Contributor" shall mean Licensor and any individual or Legal Entity
on behalf of whom a Contribution has been received by Licensor and
subsequently incorporated within the Work.
2. Grant of Copyright License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
copyright license to reproduce, prepare Derivative Works of,
publicly display, publicly perform, sublicense, and distribute the
Work and such Derivative Works in Source or Object form.
3. Grant of Patent License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
(except as stated in this section) patent license to make, have made,
use, offer to sell, sell, import, and otherwise transfer the Work,
where such license applies only to those patent claims licensable
by such Contributor that are necessarily infringed by their
Contribution(s) alone or by combination of their Contribution(s)
with the Work to which such Contribution(s) was submitted. If You
institute patent litigation against any entity (including a
cross-claim or counterclaim in a lawsuit) alleging that the Work
or a Contribution incorporated within the Work constitutes direct
or contributory patent infringement, then any patent licenses
granted to You under this License for that Work shall terminate
as of the date such litigation is filed.
4. Redistribution. You may reproduce and distribute copies of the
Work or Derivative Works thereof in any medium, with or without
modifications, and in Source or Object form, provided that You
meet the following conditions:
(a) You must give any other recipients of the Work or
Derivative Works a copy of this License; and
(b) You must cause any modified files to carry prominent notices
stating that You changed the files; and
(c) You must retain, in the Source form of any Derivative Works
that You distribute, all copyright, patent, trademark, and
attribution notices from the Source form of the Work,
excluding those notices that do not pertain to any part of
the Derivative Works; and
(d) If the Work includes a "NOTICE" text file as part of its
distribution, then any Derivative Works that You distribute must
include a readable copy of the attribution notices contained
within such NOTICE file, excluding those notices that do not
pertain to any part of the Derivative Works, in at least one
of the following places: within a NOTICE text file distributed
as part of the Derivative Works; within the Source form or
documentation, if provided along with the Derivative Works; or,
within a display generated by the Derivative Works, if and
wherever such third-party notices normally appear. The contents
of the NOTICE file are for informational purposes only and
do not modify the License. You may add Your own attribution
notices within Derivative Works that You distribute, alongside
or as an addendum to the NOTICE text from the Work, provided
that such additional attribution notices cannot be construed
as modifying the License.
You may add Your own copyright statement to Your modifications and
may provide additional or different license terms and conditions
for use, reproduction, or distribution of Your modifications, or
for any such Derivative Works as a whole, provided Your use,
reproduction, and distribution of the Work otherwise complies with
the conditions stated in this License.
5. Submission of Contributions. Unless You explicitly state otherwise,
any Contribution intentionally submitted for inclusion in the Work
by You to the Licensor shall be under the terms and conditions of
this License, without any additional terms or conditions.
Notwithstanding the above, nothing herein shall supersede or modify
the terms of any separate license agreement you may have executed
with Licensor regarding such Contributions.
6. Trademarks. This License does not grant permission to use the trade
names, trademarks, service marks, or product names of the Licensor,
except as required for reasonable and customary use in describing the
origin of the Work and reproducing the content of the NOTICE file.
7. Disclaimer of Warranty. Unless required by applicable law or
agreed to in writing, Licensor provides the Work (and each
Contributor provides its Contributions) on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
implied, including, without limitation, any warranties or conditions
of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
PARTICULAR PURPOSE. You are solely responsible for determining the
appropriateness of using or redistributing the Work and assume any
risks associated with Your exercise of permissions under this License.
8. Limitation of Liability. In no event and under no legal theory,
whether in tort (including negligence), contract, or otherwise,
unless required by applicable law (such as deliberate and grossly
negligent acts) or agreed to in writing, shall any Contributor be
liable to You for damages, including any direct, indirect, special,
incidental, or consequential damages of any character arising as a
result of this License or out of the use or inability to use the
Work (including but not limited to damages for loss of goodwill,
work stoppage, computer failure or malfunction, or any and all
other commercial damages or losses), even if such Contributor
has been advised of the possibility of such damages.
9. Accepting Warranty or Additional Liability. While redistributing
the Work or Derivative Works thereof, You may choose to offer,
and charge a fee for, acceptance of support, warranty, indemnity,
or other liability obligations and/or rights consistent with this
License. However, in accepting such obligations, You may act only
on Your own behalf and on Your sole responsibility, not on behalf
of any other Contributor, and only if You agree to indemnify,
defend, and hold each Contributor harmless for any liability
incurred by, or claims asserted against, such Contributor by reason
of your accepting any such warranty or additional liability.
END OF TERMS AND CONDITIONS
APPENDIX: How to apply the Apache License to your work.
To apply the Apache License to your work, attach the following
boilerplate notice, with the fields enclosed by brackets "[]"
replaced with your own identifying information. (Don't include
the brackets!) The text should be enclosed in the appropriate
comment syntax for the file format. We also recommend that a
file or class name and description of purpose be included on the
same "printed page" as the copyright notice for easier
identification within third-party archives.
Copyright [yyyy] [name of copyright owner]
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.

@ -1,16 +1,358 @@
# ESP32 MJPEG Multiclient Streaming Server
# ESP32 Camera Driver
This is a simple MJPEG streaming webserver implemented for AI-Thinker ESP32-CAM or ESP-EYE modules.
## General Information
This is tested to work with **VLC** and **Blynk** video widget.
This repository hosts ESP32, ESP32-S2 and ESP32-S3 compatible driver for OV2640, OV3660, OV5640, OV7670 and OV7725 image sensors. Additionally it provides a few tools, which allow converting the captured frame data to the more common BMP and JPEG formats.
## Important to Remember
- Except when using CIF or lower resolution with JPEG, the driver requires PSRAM to be installed and activated.
- Using YUV or RGB puts a lot of strain on the chip because writing to PSRAM is not particularly fast. The result is that image data might be missing. This is particularly true if WiFi is enabled. If you need RGB data, it is recommended that JPEG is captured and then turned into RGB using `fmt2rgb888` or `fmt2bmp`/`frame2bmp`.
- When 1 frame buffer is used, the driver will wait for the current frame to finish (VSYNC) and start I2S DMA. After the frame is acquired, I2S will be stopped and the frame buffer returned to the application. This approach gives more control over the system, but results in longer time to get the frame.
- When 2 or more frame bufers are used, I2S is running in continuous mode and each frame is pushed to a queue that the application can access. This approach puts more strain on the CPU/Memory, but allows for double the frame rate. Please use only with JPEG.
**This version uses FreeRTOS tasks to enable streaming to up to 10 connected clients**
## Installation Instructions
### Using esp-idf
Inspired by and based on this Instructable: [$9 RTSP Video Streamer Using the ESP32-CAM Board](https://www.instructables.com/id/9-RTSP-Video-Streamer-Using-the-ESP32-CAM-Board/)
- Clone or download and extract the repository to the components folder of your ESP-IDF project
- Enable PSRAM in `menuconfig` (also set Flash and PSRAM frequiencies to 80MHz)
- Include `esp_camera.h` in your code
### Using PlatformIO
The easy way -- on the `env` section of `platformio.ini`, add the following:
```ini
[env]
lib_deps =
esp32-camera
```
Now the `esp_camera.h` is available to be included:
```c
#include "esp_camera.h"
```
Enable PSRAM on `menuconfig` or type it direclty on `sdkconfig`. Check the [official doc](https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-reference/kconfig.html#config-esp32-spiram-support) for more info.
```
CONFIG_ESP32_SPIRAM_SUPPORT=y
```
***Arduino*** The easy-way (content above) only seems to work if you're using `framework=arduino` which seems to take a bunch of the guesswork out (thanks Arduino!) but also suck up a lot more memory and flash, almost crippling the performance. If you plan to use the `framework=espidf` then read the sections below carefully!!
## Platform.io lib/submodule (for framework=espidf)
It's probably easier to just skip the platform.io library registry version and link the git repo as a submodule. (i.e. using code outside the platform.io library management). In this example we will install this as a submodule inside the platform.io $project/lib folder:
```
cd $project\lib
git submodule add -b master https://github.com/espressif/esp32-camera.git
```
Then in `platformio.ini` file
```
build_flags =
-I../lib/esp32-camera
```
After that `#include "esp_camera.h"` statement will be available. Now the module is included, and you're hopefully back to the same place as the easy-Arduino way.
**Warning about platform.io/espidf and fresh (not initialized) git repos**
There is a sharp-edge on you'll discover in the platform.io build process (in espidf v3.3 & 4.0.1) where a project which has only had `git init` but nothing committed will crash platform.io build process with highly non-useful output. The cause is due to lack of a version (making you think you did something wrong, when you didn't at all) - the output is horribly non-descript. Solution: the devs want you to create a file called version.txt with a number in it, or simply commit any file to the projects git repo and use git. This happens because platform.io build process tries to be too clever and determine the build version number from the git repo - it's a sharp edge you'll only encounter if you're experimenting on a new project with no commits .. like wtf is my camera not working let's try a 'clean project'?! </rant>
## Platform.io Kconfig
Kconfig is used by the platform.io menuconfig (accessed by running: `pio run -t menuconfig`) to interactively manage the various #ifdef statements throughout the espidf and supporting libraries (i.e. this repo: esp32-camera and arduino-esp32.git). The menuconfig process generates the `sdkconfig` file which is ultimately used behind the scenes by espidf compile+build process.
**Make sure to append or symlink** [this `Kconfig`](./Kconfig) content into the `Kconfig` of your project.
You symlink (or copy) the included Kconfig into your platform.io projects src directory. The file should be named `Kconfig.projbuild` in your projects src\ directory or you could also add the library path to a CMakefile.txt and hope the `Kconfig` (or `Kconfig.projbuild`) gets discovered by the menuconfig process, though this unpredictable for me.
The unpredictable wonky behavior in platform.io build process around Kconfig naming (Kconfig vs. Kconfig.projbuild) occurs between espidf versions 3.3 and 4.0 - but if you don't see "Camera configuration" in your `pio run -t menuconfig` then there is no point trying to test camera code (it may compile, but it probably won't work!) and it seems the platform.io devs (when they built their wrapper around the espidf menuconfig) didn't implement it properly. You've probably already figured out you can't use the espidf build tools since the files are in totally different locations and also different versions with sometimes different syntax. This is one of those times you might consider changing the `platformio.ini` from `platform=espressif32` to `platform=https://github.com/platformio/platform-espressif32.git#develop` to get a more recent version of the espidf 4.0 tools.
However with a bit of patience and experimenting you'll figure the Kconfig out. Once Kconfig (or Kconfig.projbuild) is working then you will be able to choose the configurations according to your setup or the camera libraries will be compiled. Although you might also need to delete your .pio/build directory before the options appear .. again, the `pio run -t menuconfig` doens't always notice the new Kconfig files!
If you miss-skip-ignore this critical step the camera module will compile but camera logic inside the library will be 'empty' because the Kconfig sets the proper #ifdef statements during the build process to initialize the selected cameras. It's very not optional!
### Kconfig options
| config | description | default |
| --------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------ |
| CONFIG_OV2640_SUPPORT | Support for OV2640 camera | enabled |
| CONFIG_OV7725_SUPPORT | Support for OV7725 camera | disabled |
| CONFIG_OV3660_SUPPORT | Support for OV3660 camera | enabled |
| CONFIG_OV5640_SUPPORT | Support for OV5640 camera | enabled |
| CONFIG_SCCB_HARDWARE_I2C | Enable this option if you want to use hardware I2C to control the camera. Disable this option to use software I2C. | enabled |
| CONFIG_SCCB_HARDWARE_I2C_PORT | I2C peripheral to use for SCCB. Can be I2C0 and I2C1. | CONFIG_SCCB_HARDWARE_I2C_PORT1 |
| CONFIG_CAMERA_TASK_PINNED_TO_CORE | Pin the camera handle task to a certain core(0/1). It can also be done automatically choosing NO_AFFINITY. Can be CAMERA_CORE0, CAMERA_CORE1 or NO_AFFINITY. | CONFIG_CAMERA_CORE0 |
## Examples
### Initialization
```c
#include "esp_camera.h"
//WROVER-KIT PIN Map
#define CAM_PIN_PWDN -1 //power down is not used
#define CAM_PIN_RESET -1 //software reset will be performed
#define CAM_PIN_XCLK 21
#define CAM_PIN_SIOD 26
#define CAM_PIN_SIOC 27
#define CAM_PIN_D7 35
#define CAM_PIN_D6 34
#define CAM_PIN_D5 39
#define CAM_PIN_D4 36
#define CAM_PIN_D3 19
#define CAM_PIN_D2 18
#define CAM_PIN_D1 5
#define CAM_PIN_D0 4
#define CAM_PIN_VSYNC 25
#define CAM_PIN_HREF 23
#define CAM_PIN_PCLK 22
static camera_config_t camera_config = {
.pin_pwdn = CAM_PIN_PWDN,
.pin_reset = CAM_PIN_RESET,
.pin_xclk = CAM_PIN_XCLK,
.pin_sscb_sda = CAM_PIN_SIOD,
.pin_sscb_scl = CAM_PIN_SIOC,
.pin_d7 = CAM_PIN_D7,
.pin_d6 = CAM_PIN_D6,
.pin_d5 = CAM_PIN_D5,
.pin_d4 = CAM_PIN_D4,
.pin_d3 = CAM_PIN_D3,
.pin_d2 = CAM_PIN_D2,
.pin_d1 = CAM_PIN_D1,
.pin_d0 = CAM_PIN_D0,
.pin_vsync = CAM_PIN_VSYNC,
.pin_href = CAM_PIN_HREF,
.pin_pclk = CAM_PIN_PCLK,
.xclk_freq_hz = 20000000,//EXPERIMENTAL: Set to 16MHz on ESP32-S2 or ESP32-S3 to enable EDMA mode
.ledc_timer = LEDC_TIMER_0,
.ledc_channel = LEDC_CHANNEL_0,
.pixel_format = PIXFORMAT_JPEG,//YUV422,GRAYSCALE,RGB565,JPEG
.frame_size = FRAMESIZE_UXGA,//QQVGA-QXGA Do not use sizes above QVGA when not JPEG
.jpeg_quality = 12, //0-63 lower number means higher quality
.fb_count = 1, //if more than one, i2s runs in continuous mode. Use only with JPEG
.grab_mode = CAMERA_GRAB_WHEN_EMPTY//CAMERA_GRAB_LATEST. Sets when buffers should be filled
};
esp_err_t camera_init(){
//power up the camera if PWDN pin is defined
if(CAM_PIN_PWDN != -1){
pinMode(CAM_PIN_PWDN, OUTPUT);
digitalWrite(CAM_PIN_PWDN, LOW);
}
//initialize the camera
esp_err_t err = esp_camera_init(&camera_config);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Camera Init Failed");
return err;
}
return ESP_OK;
}
esp_err_t camera_capture(){
//acquire a frame
camera_fb_t * fb = esp_camera_fb_get();
if (!fb) {
ESP_LOGE(TAG, "Camera Capture Failed");
return ESP_FAIL;
}
//replace this with your own function
process_image(fb->width, fb->height, fb->format, fb->buf, fb->len);
//return the frame buffer back to the driver for reuse
esp_camera_fb_return(fb);
return ESP_OK;
}
```
### JPEG HTTP Capture
```c
#include "esp_camera.h"
#include "esp_http_server.h"
#include "esp_timer.h"
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;
}
esp_err_t jpg_httpd_handler(httpd_req_t *req){
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(TAG, "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(TAG, "JPG: %uKB %ums", (uint32_t)(fb_len/1024), (uint32_t)((fr_end - fr_start)/1000));
return res;
}
```
### JPEG HTTP Stream
```c
#include "esp_camera.h"
#include "esp_http_server.h"
#include "esp_timer.h"
#define PART_BOUNDARY "123456789000000000000987654321"
static const char* _STREAM_CONTENT_TYPE = "multipart/x-mixed-replace;boundary=" PART_BOUNDARY;
static const char* _STREAM_BOUNDARY = "\r\n--" PART_BOUNDARY "\r\n";
static const char* _STREAM_PART = "Content-Type: image/jpeg\r\nContent-Length: %u\r\n\r\n";
esp_err_t jpg_stream_httpd_handler(httpd_req_t *req){
camera_fb_t * fb = NULL;
esp_err_t res = ESP_OK;
size_t _jpg_buf_len;
uint8_t * _jpg_buf;
char * part_buf[64];
static int64_t last_frame = 0;
if(!last_frame) {
last_frame = esp_timer_get_time();
}
res = httpd_resp_set_type(req, _STREAM_CONTENT_TYPE);
if(res != ESP_OK){
return res;
}
while(true){
fb = esp_camera_fb_get();
if (!fb) {
ESP_LOGE(TAG, "Camera capture failed");
res = ESP_FAIL;
break;
}
if(fb->format != PIXFORMAT_JPEG){
bool jpeg_converted = frame2jpg(fb, 80, &_jpg_buf, &_jpg_buf_len);
if(!jpeg_converted){
ESP_LOGE(TAG, "JPEG compression failed");
esp_camera_fb_return(fb);
res = ESP_FAIL;
}
} else {
_jpg_buf_len = fb->len;
_jpg_buf = fb->buf;
}
if(res == ESP_OK){
res = httpd_resp_send_chunk(req, _STREAM_BOUNDARY, strlen(_STREAM_BOUNDARY));
}
if(res == ESP_OK){
size_t hlen = snprintf((char *)part_buf, 64, _STREAM_PART, _jpg_buf_len);
res = httpd_resp_send_chunk(req, (const char *)part_buf, hlen);
}
if(res == ESP_OK){
res = httpd_resp_send_chunk(req, (const char *)_jpg_buf, _jpg_buf_len);
}
if(fb->format != PIXFORMAT_JPEG){
free(_jpg_buf);
}
esp_camera_fb_return(fb);
if(res != ESP_OK){
break;
}
int64_t fr_end = esp_timer_get_time();
int64_t frame_time = fr_end - last_frame;
last_frame = fr_end;
frame_time /= 1000;
ESP_LOGI(TAG, "MJPG: %uKB %ums (%.1ffps)",
(uint32_t)(_jpg_buf_len/1024),
(uint32_t)frame_time, 1000.0 / (uint32_t)frame_time);
}
last_frame = 0;
return res;
}
```
### BMP HTTP Capture
```c
#include "esp_camera.h"
#include "esp_http_server.h"
#include "esp_timer.h"
esp_err_t bmp_httpd_handler(httpd_req_t *req){
camera_fb_t * fb = NULL;
esp_err_t res = ESP_OK;
int64_t fr_start = esp_timer_get_time();
fb = esp_camera_fb_get();
if (!fb) {
ESP_LOGE(TAG, "Camera capture failed");
httpd_resp_send_500(req);
return ESP_FAIL;
}
uint8_t * buf = NULL;
size_t buf_len = 0;
bool converted = frame2bmp(fb, &buf, &buf_len);
esp_camera_fb_return(fb);
if(!converted){
ESP_LOGE(TAG, "BMP conversion failed");
httpd_resp_send_500(req);
return ESP_FAIL;
}
res = httpd_resp_set_type(req, "image/x-windows-bmp")
|| httpd_resp_set_hdr(req, "Content-Disposition", "inline; filename=capture.bmp")
|| httpd_resp_send(req, (const char *)buf, buf_len);
free(buf);
int64_t fr_end = esp_timer_get_time();
ESP_LOGI(TAG, "BMP: %uKB %ums", (uint32_t)(buf_len/1024), (uint32_t)((fr_end - fr_start)/1000));
return res;
}
```

@ -0,0 +1,472 @@
// Copyright 2010-2020 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.
#include <stdio.h>
#include <string.h>
#include "esp_heap_caps.h"
#include "ll_cam.h"
#include "cam_hal.h"
static const char *TAG = "cam_hal";
static cam_obj_t *cam_obj = NULL;
static const uint32_t JPEG_SOI_MARKER = 0xFFD8FF; // written in little-endian for esp32
static const uint16_t JPEG_EOI_MARKER = 0xD9FF; // written in little-endian for esp32
static int cam_verify_jpeg_soi(const uint8_t *inbuf, uint32_t length)
{
uint32_t sig = *((uint32_t *)inbuf) & 0xFFFFFF;
if(sig != JPEG_SOI_MARKER) {
for (uint32_t i = 0; i < length; i++) {
sig = *((uint32_t *)(&inbuf[i])) & 0xFFFFFF;
if (sig == JPEG_SOI_MARKER) {
ESP_LOGW(TAG, "SOI: %d", i);
return i;
}
}
ESP_LOGW(TAG, "NO-SOI");
return -1;
}
return 0;
}
static int cam_verify_jpeg_eoi(const uint8_t *inbuf, uint32_t length)
{
int offset = -1;
uint8_t *dptr = (uint8_t *)inbuf + length - 2;
while (dptr > inbuf) {
uint16_t sig = *((uint16_t *)dptr);
if (JPEG_EOI_MARKER == sig) {
offset = dptr - inbuf;
//ESP_LOGW(TAG, "EOI: %d", length - (offset + 2));
return offset;
}
dptr--;
}
return -1;
}
static bool cam_get_next_frame(int * frame_pos)
{
if(!cam_obj->frames[*frame_pos].en){
for (int x = 0; x < cam_obj->frame_cnt; x++) {
if (cam_obj->frames[x].en) {
*frame_pos = x;
return true;
}
}
} else {
return true;
}
return false;
}
static bool cam_start_frame(int * frame_pos)
{
if (cam_get_next_frame(frame_pos)) {
if(ll_cam_start(cam_obj, *frame_pos)){
// Vsync the frame manually
ll_cam_do_vsync(cam_obj);
uint64_t us = (uint64_t)esp_timer_get_time();
cam_obj->frames[*frame_pos].fb.timestamp.tv_sec = us / 1000000UL;
cam_obj->frames[*frame_pos].fb.timestamp.tv_usec = us % 1000000UL;
return true;
}
}
return false;
}
void IRAM_ATTR ll_cam_send_event(cam_obj_t *cam, cam_event_t cam_event, BaseType_t * HPTaskAwoken)
{
if (xQueueSendFromISR(cam->event_queue, (void *)&cam_event, HPTaskAwoken) != pdTRUE) {
ll_cam_stop(cam);
cam->state = CAM_STATE_IDLE;
ESP_EARLY_LOGE(TAG, "EV-OVF");
}
}
//Copy fram from DMA dma_buffer to fram dma_buffer
static void cam_task(void *arg)
{
int cnt = 0;
int frame_pos = 0;
cam_obj->state = CAM_STATE_IDLE;
cam_event_t cam_event = 0;
xQueueReset(cam_obj->event_queue);
while (1) {
xQueueReceive(cam_obj->event_queue, (void *)&cam_event, portMAX_DELAY);
DBG_PIN_SET(1);
switch (cam_obj->state) {
case CAM_STATE_IDLE: {
if (cam_event == CAM_VSYNC_EVENT) {
//DBG_PIN_SET(1);
if(cam_start_frame(&frame_pos)){
cam_obj->frames[frame_pos].fb.len = 0;
cam_obj->state = CAM_STATE_READ_BUF;
}
cnt = 0;
}
}
break;
case CAM_STATE_READ_BUF: {
camera_fb_t * frame_buffer_event = &cam_obj->frames[frame_pos].fb;
size_t pixels_per_dma = (cam_obj->dma_half_buffer_size * cam_obj->fb_bytes_per_pixel) / (cam_obj->dma_bytes_per_item * cam_obj->in_bytes_per_pixel);
if (cam_event == CAM_IN_SUC_EOF_EVENT) {
if(!cam_obj->psram_mode){
if (cam_obj->fb_size < (frame_buffer_event->len + pixels_per_dma)) {
ESP_LOGW(TAG, "FB-OVF");
ll_cam_stop(cam_obj);
DBG_PIN_SET(0);
continue;
}
frame_buffer_event->len += ll_cam_memcpy(cam_obj,
&frame_buffer_event->buf[frame_buffer_event->len],
&cam_obj->dma_buffer[(cnt % cam_obj->dma_half_buffer_cnt) * cam_obj->dma_half_buffer_size],
cam_obj->dma_half_buffer_size);
}
//Check for JPEG SOI in the first buffer. stop if not found
if (cam_obj->jpeg_mode && cnt == 0 && cam_verify_jpeg_soi(frame_buffer_event->buf, frame_buffer_event->len) != 0) {
ll_cam_stop(cam_obj);
cam_obj->state = CAM_STATE_IDLE;
}
cnt++;
} else if (cam_event == CAM_VSYNC_EVENT) {
//DBG_PIN_SET(1);
ll_cam_stop(cam_obj);
if (cnt || !cam_obj->jpeg_mode || cam_obj->psram_mode) {
if (cam_obj->jpeg_mode) {
if (!cam_obj->psram_mode) {
if (cam_obj->fb_size < (frame_buffer_event->len + pixels_per_dma)) {
ESP_LOGW(TAG, "FB-OVF");
cnt--;
} else {
frame_buffer_event->len += ll_cam_memcpy(cam_obj,
&frame_buffer_event->buf[frame_buffer_event->len],
&cam_obj->dma_buffer[(cnt % cam_obj->dma_half_buffer_cnt) * cam_obj->dma_half_buffer_size],
cam_obj->dma_half_buffer_size);
}
}
cnt++;
}
cam_obj->frames[frame_pos].en = 0;
if (cam_obj->psram_mode) {
if (cam_obj->jpeg_mode) {
frame_buffer_event->len = cnt * cam_obj->dma_half_buffer_size;
} else {
frame_buffer_event->len = cam_obj->recv_size;
}
} else if (!cam_obj->jpeg_mode) {
if (frame_buffer_event->len != cam_obj->fb_size) {
cam_obj->frames[frame_pos].en = 1;
ESP_LOGE(TAG, "FB-SIZE: %u != %u", frame_buffer_event->len, cam_obj->fb_size);
}
}
//send frame
if(!cam_obj->frames[frame_pos].en && xQueueSend(cam_obj->frame_buffer_queue, (void *)&frame_buffer_event, 0) != pdTRUE) {
//pop frame buffer from the queue
camera_fb_t * fb2 = NULL;
if(xQueueReceive(cam_obj->frame_buffer_queue, &fb2, 0) == pdTRUE) {
//push the new frame to the end of the queue
if (xQueueSend(cam_obj->frame_buffer_queue, (void *)&frame_buffer_event, 0) != pdTRUE) {
cam_obj->frames[frame_pos].en = 1;
ESP_LOGE(TAG, "FBQ-SND");
}
//free the popped buffer
cam_give(fb2);
} else {
//queue is full and we could not pop a frame from it
cam_obj->frames[frame_pos].en = 1;
ESP_LOGE(TAG, "FBQ-RCV");
}
}
}
if(!cam_start_frame(&frame_pos)){
cam_obj->state = CAM_STATE_IDLE;
} else {
cam_obj->frames[frame_pos].fb.len = 0;
}
cnt = 0;
}
}
break;
}
DBG_PIN_SET(0);
}
}
static lldesc_t * allocate_dma_descriptors(uint32_t count, uint16_t size, uint8_t * buffer)
{
lldesc_t *dma = (lldesc_t *)heap_caps_malloc(count * sizeof(lldesc_t), MALLOC_CAP_DMA);
if (dma == NULL) {
return dma;
}
for (int x = 0; x < count; x++) {
dma[x].size = size;
dma[x].length = 0;
dma[x].sosf = 0;
dma[x].eof = 0;
dma[x].owner = 1;
dma[x].buf = (buffer + size * x);
dma[x].empty = (uint32_t)&dma[(x + 1) % count];
}
return dma;
}
static esp_err_t cam_dma_config()
{
bool ret = ll_cam_dma_sizes(cam_obj);
if (0 == ret) {
return ESP_FAIL;
}
cam_obj->dma_node_cnt = (cam_obj->dma_buffer_size) / cam_obj->dma_node_buffer_size; // Number of DMA nodes
cam_obj->frame_copy_cnt = cam_obj->recv_size / cam_obj->dma_half_buffer_size; // Number of interrupted copies, ping-pong copy
ESP_LOGI(TAG, "buffer_size: %d, half_buffer_size: %d, node_buffer_size: %d, node_cnt: %d, total_cnt: %d",
cam_obj->dma_buffer_size, cam_obj->dma_half_buffer_size, cam_obj->dma_node_buffer_size, cam_obj->dma_node_cnt, cam_obj->frame_copy_cnt);
cam_obj->dma_buffer = NULL;
cam_obj->dma = NULL;
cam_obj->frames = (cam_frame_t *)heap_caps_calloc(1, cam_obj->frame_cnt * sizeof(cam_frame_t), MALLOC_CAP_DEFAULT);
CAM_CHECK(cam_obj->frames != NULL, "frames malloc failed", ESP_FAIL);
uint8_t dma_align = 0;
size_t fb_size = cam_obj->fb_size;
if (cam_obj->psram_mode) {
dma_align = ll_cam_get_dma_align(cam_obj);
if (cam_obj->fb_size < cam_obj->recv_size) {
fb_size = cam_obj->recv_size;
}
}
for (int x = 0; x < cam_obj->frame_cnt; x++) {
cam_obj->frames[x].dma = NULL;
cam_obj->frames[x].fb_offset = 0;
cam_obj->frames[x].en = 0;
cam_obj->frames[x].fb.buf = (uint8_t *)heap_caps_malloc(fb_size * sizeof(uint8_t) + dma_align, MALLOC_CAP_SPIRAM);
CAM_CHECK(cam_obj->frames[x].fb.buf != NULL, "frame buffer malloc failed", ESP_FAIL);
if (cam_obj->psram_mode) {
//align PSRAM buffer. TODO: save the offset so proper address can be freed later
cam_obj->frames[x].fb_offset = dma_align - ((uint32_t)cam_obj->frames[x].fb.buf & (dma_align - 1));
cam_obj->frames[x].fb.buf += cam_obj->frames[x].fb_offset;
ESP_LOGI(TAG, "Frame[%d]: Offset: %u, Addr: 0x%08X", x, cam_obj->frames[x].fb_offset, (uint32_t)cam_obj->frames[x].fb.buf);
cam_obj->frames[x].dma = allocate_dma_descriptors(cam_obj->dma_node_cnt, cam_obj->dma_node_buffer_size, cam_obj->frames[x].fb.buf);
CAM_CHECK(cam_obj->frames[x].dma != NULL, "frame dma malloc failed", ESP_FAIL);
}
cam_obj->frames[x].en = 1;
}
if (!cam_obj->psram_mode) {
cam_obj->dma_buffer = (uint8_t *)heap_caps_malloc(cam_obj->dma_buffer_size * sizeof(uint8_t), MALLOC_CAP_DMA);
CAM_CHECK(cam_obj->dma_buffer != NULL, "dma_buffer malloc failed", ESP_FAIL);
cam_obj->dma = allocate_dma_descriptors(cam_obj->dma_node_cnt, cam_obj->dma_node_buffer_size, cam_obj->dma_buffer);
CAM_CHECK(cam_obj->dma != NULL, "dma malloc failed", ESP_FAIL);
}
return ESP_OK;
}
esp_err_t cam_init(const camera_config_t *config)
{
CAM_CHECK(NULL != config, "config pointer is invalid", ESP_ERR_INVALID_ARG);
esp_err_t ret = ESP_OK;
cam_obj = (cam_obj_t *)heap_caps_calloc(1, sizeof(cam_obj_t), MALLOC_CAP_DMA);
CAM_CHECK(NULL != cam_obj, "lcd_cam object malloc error", ESP_ERR_NO_MEM);
cam_obj->swap_data = 0;
cam_obj->vsync_pin = config->pin_vsync;
cam_obj->vsync_invert = true;
ll_cam_set_pin(cam_obj, config);
ret = ll_cam_config(cam_obj, config);
CAM_CHECK_GOTO(ret == ESP_OK, "ll_cam initialize failed", err);
#if CAMERA_DBG_PIN_ENABLE
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[DBG_PIN_NUM], PIN_FUNC_GPIO);
gpio_set_direction(DBG_PIN_NUM, GPIO_MODE_OUTPUT);
gpio_set_pull_mode(DBG_PIN_NUM, GPIO_FLOATING);
#endif
ESP_LOGI(TAG, "cam init ok");
return ESP_OK;
err:
free(cam_obj);
cam_obj = NULL;
return ESP_FAIL;
}
esp_err_t cam_config(const camera_config_t *config, framesize_t frame_size, uint8_t sensor_pid)
{
CAM_CHECK(NULL != config, "config pointer is invalid", ESP_ERR_INVALID_ARG);
esp_err_t ret = ESP_OK;
ret = ll_cam_set_sample_mode(cam_obj, (pixformat_t)config->pixel_format, config->xclk_freq_hz, sensor_pid);
cam_obj->jpeg_mode = config->pixel_format == PIXFORMAT_JPEG;
#if CONFIG_IDF_TARGET_ESP32
cam_obj->psram_mode = false;
#else
cam_obj->psram_mode = (config->xclk_freq_hz == 16000000);
#endif
cam_obj->frame_cnt = config->fb_count;
cam_obj->width = resolution[frame_size].width;
cam_obj->height = resolution[frame_size].height;
if(cam_obj->jpeg_mode){
cam_obj->recv_size = cam_obj->width * cam_obj->height / 5;
cam_obj->fb_size = cam_obj->recv_size;
} else {
cam_obj->recv_size = cam_obj->width * cam_obj->height * cam_obj->in_bytes_per_pixel;
cam_obj->fb_size = cam_obj->width * cam_obj->height * cam_obj->fb_bytes_per_pixel;
}
ret = cam_dma_config();
CAM_CHECK_GOTO(ret == ESP_OK, "cam_dma_config failed", err);
cam_obj->event_queue = xQueueCreate(cam_obj->dma_half_buffer_cnt - 1, sizeof(cam_event_t));
CAM_CHECK_GOTO(cam_obj->event_queue != NULL, "event_queue create failed", err);
size_t frame_buffer_queue_len = cam_obj->frame_cnt;
if (config->grab_mode == CAMERA_GRAB_LATEST && cam_obj->frame_cnt > 1) {
frame_buffer_queue_len = cam_obj->frame_cnt - 1;
}
cam_obj->frame_buffer_queue = xQueueCreate(frame_buffer_queue_len, sizeof(camera_fb_t*));
CAM_CHECK_GOTO(cam_obj->frame_buffer_queue != NULL, "frame_buffer_queue create failed", err);
ret = ll_cam_init_isr(cam_obj);
CAM_CHECK_GOTO(ret == ESP_OK, "cam intr alloc failed", err);
#if CONFIG_CAMERA_CORE0
xTaskCreatePinnedToCore(cam_task, "cam_task", 2048, NULL, configMAX_PRIORITIES - 2, &cam_obj->task_handle, 0);
#elif CONFIG_CAMERA_CORE1
xTaskCreatePinnedToCore(cam_task, "cam_task", 2048, NULL, configMAX_PRIORITIES - 2, &cam_obj->task_handle, 1);
#else
xTaskCreate(cam_task, "cam_task", 2048, NULL, configMAX_PRIORITIES - 2, &cam_obj->task_handle);
#endif
ESP_LOGI(TAG, "cam config ok");
return ESP_OK;
err:
cam_deinit();
return ESP_FAIL;
}
esp_err_t cam_deinit(void)
{
if (!cam_obj) {
return ESP_FAIL;
}
cam_stop();
gpio_isr_handler_remove(cam_obj->vsync_pin);
if (cam_obj->task_handle) {
vTaskDelete(cam_obj->task_handle);
}
if (cam_obj->event_queue) {
vQueueDelete(cam_obj->event_queue);
}
if (cam_obj->frame_buffer_queue) {
vQueueDelete(cam_obj->frame_buffer_queue);
}
if (cam_obj->dma) {
free(cam_obj->dma);
}
if (cam_obj->dma_buffer) {
free(cam_obj->dma_buffer);
}
if (cam_obj->frames) {
for (int x = 0; x < cam_obj->frame_cnt; x++) {
free(cam_obj->frames[x].fb.buf - cam_obj->frames[x].fb_offset);
if (cam_obj->frames[x].dma) {
free(cam_obj->frames[x].dma);
}
}
free(cam_obj->frames);
}
if (cam_obj->cam_intr_handle) {
esp_intr_free(cam_obj->cam_intr_handle);
}
free(cam_obj);
cam_obj = NULL;
return ESP_OK;
}
void cam_stop(void)
{
ll_cam_vsync_intr_enable(cam_obj, false);
ll_cam_stop(cam_obj);
}
void cam_start(void)
{
ll_cam_vsync_intr_enable(cam_obj, true);
}
camera_fb_t *cam_take(TickType_t timeout)
{
camera_fb_t *dma_buffer = NULL;
TickType_t start = xTaskGetTickCount();
xQueueReceive(cam_obj->frame_buffer_queue, (void *)&dma_buffer, timeout);
if (dma_buffer) {
if(cam_obj->jpeg_mode){
// find the end marker for JPEG. Data after that can be discarded
int offset_e = cam_verify_jpeg_eoi(dma_buffer->buf, dma_buffer->len);
if (offset_e >= 0) {
// adjust buffer length
dma_buffer->len = offset_e + sizeof(JPEG_EOI_MARKER);
return dma_buffer;
} else {
ESP_LOGW(TAG, "NO-EOI");
cam_give(dma_buffer);
return cam_take(timeout - (xTaskGetTickCount() - start));//recurse!!!!
}
} else if(cam_obj->psram_mode && cam_obj->in_bytes_per_pixel != cam_obj->fb_bytes_per_pixel){
//currently this is used only for YUV to GRAYSCALE
dma_buffer->len = ll_cam_memcpy(cam_obj, dma_buffer->buf, dma_buffer->buf, dma_buffer->len);
}
return dma_buffer;
} else {
ESP_LOGI(TAG, "Failed to get the frame on time!");
}
return NULL;
}
void cam_give(camera_fb_t *dma_buffer)
{
for (int x = 0; x < cam_obj->frame_cnt; x++) {
if (&cam_obj->frames[x].fb == dma_buffer) {
cam_obj->frames[x].en = 1;
break;
}
}
}

@ -0,0 +1,60 @@
// Copyright 2010-2020 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.
#pragma once
#include "esp_camera.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Uninitialize the lcd_cam module
*
* @param handle Provide handle pointer to release resources
*
* @return
* - ESP_OK Success
* - ESP_FAIL Uninitialize fail
*/
esp_err_t cam_deinit(void);
/**
* @brief Initialize the lcd_cam module
*
* @param config Configurations - see lcd_cam_config_t struct
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
* - ESP_ERR_NO_MEM No memory to initialize lcd_cam
* - ESP_FAIL Initialize fail
*/
esp_err_t cam_init(const camera_config_t *config);
esp_err_t cam_config(const camera_config_t *config, framesize_t frame_size, uint8_t sensor_pid);
void cam_stop(void);
void cam_start(void);
camera_fb_t *cam_take(TickType_t timeout);
void cam_give(camera_fb_t *dma_buffer);
#ifdef __cplusplus
}
#endif

File diff suppressed because it is too large Load Diff

@ -15,6 +15,10 @@
#if ESP_IDF_VERSION_MAJOR >= 4 // IDF 4+
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
#include "esp32/rom/lldesc.h"
#elif CONFIG_IDF_TARGET_ESP32S2 // ESP32-S2
#include "esp32s2/rom/lldesc.h"
#elif CONFIG_IDF_TARGET_ESP32S3 // ESP32-S3
#include "esp32s3/rom/lldesc.h"
#else
#error Target CONFIG_IDF_TARGET is not supported
#endif
@ -22,28 +26,3 @@
#include "rom/lldesc.h"
#endif
typedef union {
struct {
uint8_t sample2;
uint8_t unused2;
uint8_t sample1;
uint8_t unused1;
};
uint32_t val;
} dma_elem_t;
typedef enum {
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 s2, 00 s2 00 s3, 00 s3 00 s4, ...
*/
SM_0A0B_0B0C = 0,
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 s2, 00 s3 00 s4, ...
*/
SM_0A0B_0C0D = 1,
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 00, 00 s2 00 00, 00 s3 00 00, ...
*/
SM_0A00_0B00 = 3,
} i2s_sampling_mode_t;

@ -0,0 +1,4 @@
COMPONENT_ADD_INCLUDEDIRS := driver/include conversions/include
COMPONENT_PRIV_INCLUDEDIRS := driver/private_include conversions/private_include sensors/private_include target/private_include
COMPONENT_SRCDIRS := driver conversions sensors target target/esp32
CXXFLAGS += -fno-rtti

Binary file not shown.

@ -0,0 +1,430 @@
// 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.
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include "time.h"
#include "sys/time.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "driver/gpio.h"
#include "esp_system.h"
#include "nvs_flash.h"
#include "nvs.h"
#include "sensor.h"
#include "sccb.h"
#include "cam_hal.h"
#include "esp_camera.h"
// #include "camera_common.h"
#include "xclk.h"
#if CONFIG_OV2640_SUPPORT
#include "ov2640.h"
#endif
#if CONFIG_OV7725_SUPPORT
#include "ov7725.h"
#endif
#if CONFIG_OV3660_SUPPORT
#include "ov3660.h"
#endif
#if CONFIG_OV5640_SUPPORT
#include "ov5640.h"
#endif
#if CONFIG_NT99141_SUPPORT
#include "nt99141.h"
#endif
#if CONFIG_OV7670_SUPPORT
#include "ov7670.h"
#endif
#if defined(ARDUINO_ARCH_ESP32) && defined(CONFIG_ARDUHAL_ESP_LOG)
#include "esp32-hal-log.h"
#define TAG ""
#else
#include "esp_log.h"
static const char *TAG = "camera";
#endif
typedef struct {
sensor_t sensor;
camera_fb_t fb;
} camera_state_t;
static const char* CAMERA_SENSOR_NVS_KEY = "sensor";
static const char* CAMERA_PIXFORMAT_NVS_KEY = "pixformat";
static camera_state_t *s_state = NULL;
#if CONFIG_IDF_TARGET_ESP32S3 // LCD_CAM module of ESP32-S3 will generate xclk
#define CAMERA_ENABLE_OUT_CLOCK(v)
#define CAMERA_DISABLE_OUT_CLOCK()
#else
#define CAMERA_ENABLE_OUT_CLOCK(v) camera_enable_out_clock((v))
#define CAMERA_DISABLE_OUT_CLOCK() camera_disable_out_clock()
#endif
static esp_err_t camera_probe(const camera_config_t *config, camera_model_t *out_camera_model)
{
*out_camera_model = CAMERA_NONE;
if (s_state != NULL) {
return ESP_ERR_INVALID_STATE;
}
s_state = (camera_state_t *) calloc(sizeof(camera_state_t), 1);
if (!s_state) {
return ESP_ERR_NO_MEM;
}
if (config->pin_xclk >= 0) {
ESP_LOGD(TAG, "Enabling XCLK output");
CAMERA_ENABLE_OUT_CLOCK(config);
}
if (config->pin_sscb_sda != -1) {
ESP_LOGD(TAG, "Initializing SSCB");
SCCB_Init(config->pin_sscb_sda, config->pin_sscb_scl);
}
if (config->pin_pwdn >= 0) {
ESP_LOGD(TAG, "Resetting camera by power down line");
gpio_config_t conf = { 0 };
conf.pin_bit_mask = 1LL << config->pin_pwdn;
conf.mode = GPIO_MODE_OUTPUT;
gpio_config(&conf);
// carefull, logic is inverted compared to reset pin
gpio_set_level(config->pin_pwdn, 1);
vTaskDelay(10 / portTICK_PERIOD_MS);
gpio_set_level(config->pin_pwdn, 0);
vTaskDelay(10 / portTICK_PERIOD_MS);
}
if (config->pin_reset >= 0) {
ESP_LOGD(TAG, "Resetting camera");
gpio_config_t conf = { 0 };
conf.pin_bit_mask = 1LL << config->pin_reset;
conf.mode = GPIO_MODE_OUTPUT;
gpio_config(&conf);
gpio_set_level(config->pin_reset, 0);
vTaskDelay(10 / portTICK_PERIOD_MS);
gpio_set_level(config->pin_reset, 1);
vTaskDelay(10 / portTICK_PERIOD_MS);
}
ESP_LOGD(TAG, "Searching for camera address");
vTaskDelay(10 / portTICK_PERIOD_MS);
uint8_t slv_addr = SCCB_Probe();
if (slv_addr == 0) {
CAMERA_DISABLE_OUT_CLOCK();
return ESP_ERR_NOT_FOUND;
}
ESP_LOGI(TAG, "Detected camera at address=0x%02x", slv_addr);
s_state->sensor.slv_addr = slv_addr;
s_state->sensor.xclk_freq_hz = config->xclk_freq_hz;
/**
* Read sensor ID
*/
sensor_id_t *id = &s_state->sensor.id;
if (slv_addr == OV2640_SCCB_ADDR || slv_addr == OV7725_SCCB_ADDR) {
SCCB_Write(slv_addr, 0xFF, 0x01);//bank sensor
id->PID = SCCB_Read(slv_addr, REG_PID);
id->VER = SCCB_Read(slv_addr, REG_VER);
id->MIDL = SCCB_Read(slv_addr, REG_MIDL);
id->MIDH = SCCB_Read(slv_addr, REG_MIDH);
} else if (slv_addr == OV5640_SCCB_ADDR || slv_addr == OV3660_SCCB_ADDR) {
id->PID = SCCB_Read16(slv_addr, REG16_CHIDH);
id->VER = SCCB_Read16(slv_addr, REG16_CHIDL);
} else if (slv_addr == NT99141_SCCB_ADDR) {
SCCB_Write16(slv_addr, 0x3008, 0x01);//bank sensor
id->PID = SCCB_Read16(slv_addr, 0x3000);
id->VER = SCCB_Read16(slv_addr, 0x3001);
if (config->xclk_freq_hz > 10000000) {
ESP_LOGE(TAG, "NT99141: only XCLK under 10MHz is supported, and XCLK is now set to 10M");
s_state->sensor.xclk_freq_hz = 10000000;
}
}
vTaskDelay(10 / portTICK_PERIOD_MS);
ESP_LOGI(TAG, "Camera PID=0x%02x VER=0x%02x MIDL=0x%02x MIDH=0x%02x",
id->PID, id->VER, id->MIDH, id->MIDL);
/**
* Initialize sensor according to sensor ID
*/
switch (id->PID) {
#if CONFIG_OV2640_SUPPORT
case OV2640_PID:
*out_camera_model = CAMERA_OV2640;
ov2640_init(&s_state->sensor);
break;
#endif
#if CONFIG_OV7725_SUPPORT
case OV7725_PID:
*out_camera_model = CAMERA_OV7725;
ov7725_init(&s_state->sensor);
break;
#endif
#if CONFIG_OV3660_SUPPORT
case OV3660_PID:
*out_camera_model = CAMERA_OV3660;
ov3660_init(&s_state->sensor);
break;
#endif
#if CONFIG_OV5640_SUPPORT
case OV5640_PID:
*out_camera_model = CAMERA_OV5640;
ov5640_init(&s_state->sensor);
break;
#endif
#if CONFIG_OV7670_SUPPORT
case OV7670_PID:
*out_camera_model = CAMERA_OV7670;
ov7670_init(&s_state->sensor);
break;
#endif
#if CONFIG_NT99141_SUPPORT
case NT99141_PID:
*out_camera_model = CAMERA_NT99141;
NT99141_init(&s_state->sensor);
break;
#endif
default:
id->PID = 0;
CAMERA_DISABLE_OUT_CLOCK();
ESP_LOGE(TAG, "Detected camera not supported.");
return ESP_ERR_NOT_SUPPORTED;
}
ESP_LOGD(TAG, "Doing SW reset of sensor");
s_state->sensor.reset(&s_state->sensor);
return ESP_OK;
}
esp_err_t esp_camera_init(const camera_config_t *config)
{
esp_err_t err;
err = cam_init(config);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Camera init failed with error 0x%x", err);
return err;
}
camera_model_t camera_model = CAMERA_NONE;
err = camera_probe(config, &camera_model);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Camera probe failed with error 0x%x(%s)", err, esp_err_to_name(err));
goto fail;
}
if (camera_model == CAMERA_OV7725) {
ESP_LOGI(TAG, "Detected OV7725 camera");
} else if (camera_model == CAMERA_OV2640) {
ESP_LOGI(TAG, "Detected OV2640 camera");
} else if (camera_model == CAMERA_OV3660) {
ESP_LOGI(TAG, "Detected OV3660 camera");
} else if (camera_model == CAMERA_OV5640) {
ESP_LOGI(TAG, "Detected OV5640 camera");
} else if (camera_model == CAMERA_OV7670) {
ESP_LOGI(TAG, "Detected OV7670 camera");
} else if (camera_model == CAMERA_NT99141) {
ESP_LOGI(TAG, "Detected NT99141 camera");
} else {
ESP_LOGI(TAG, "Camera not supported");
err = ESP_ERR_CAMERA_NOT_SUPPORTED;
goto fail;
}
framesize_t frame_size = (framesize_t) config->frame_size;
pixformat_t pix_format = (pixformat_t) config->pixel_format;
if (frame_size > camera_sensor[camera_model].max_size) {
frame_size = camera_sensor[camera_model].max_size;
}
err = cam_config(config, frame_size, s_state->sensor.id.PID);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Camera config failed with error 0x%x", err);
goto fail;
}
s_state->sensor.status.framesize = frame_size;
s_state->sensor.pixformat = pix_format;
// ESP_LOGD(TAG, "Setting frame size to %dx%d", s_state->width, s_state->height);
if (s_state->sensor.set_framesize(&s_state->sensor, frame_size) != 0) {
ESP_LOGE(TAG, "Failed to set frame size");
err = ESP_ERR_CAMERA_FAILED_TO_SET_FRAME_SIZE;
goto fail;
}
s_state->sensor.set_pixformat(&s_state->sensor, pix_format);
if (s_state->sensor.id.PID == OV2640_PID) {
s_state->sensor.set_gainceiling(&s_state->sensor, GAINCEILING_2X);
s_state->sensor.set_bpc(&s_state->sensor, false);
s_state->sensor.set_wpc(&s_state->sensor, true);
s_state->sensor.set_lenc(&s_state->sensor, true);
}
if (pix_format == PIXFORMAT_JPEG) {
(*s_state->sensor.set_quality)(&s_state->sensor, config->jpeg_quality);
}
s_state->sensor.init_status(&s_state->sensor);
cam_start();
return ESP_OK;
fail:
CAMERA_DISABLE_OUT_CLOCK();
return err;
}
esp_err_t esp_camera_deinit()
{
esp_err_t ret = cam_deinit();
if (s_state) {
SCCB_Deinit();
free(s_state);
s_state = NULL;
}
return ret;
}
#define FB_GET_TIMEOUT (4000 / portTICK_PERIOD_MS)
camera_fb_t *esp_camera_fb_get()
{
if (s_state == NULL) {
return NULL;
}
camera_fb_t *fb = cam_take(FB_GET_TIMEOUT);
//set the frame properties
if (fb) {
fb->width = resolution[s_state->sensor.status.framesize].width;
fb->height = resolution[s_state->sensor.status.framesize].height;
fb->format = s_state->sensor.pixformat;
}
return fb;
}
void esp_camera_fb_return(camera_fb_t *fb)
{
if (s_state == NULL) {
return;
}
cam_give(fb);
}
sensor_t *esp_camera_sensor_get()
{
if (s_state == NULL) {
return NULL;
}
return &s_state->sensor;
}
esp_err_t esp_camera_save_to_nvs(const char *key)
{
#if ESP_IDF_VERSION_MAJOR > 3
nvs_handle_t handle;
#else
nvs_handle handle;
#endif
esp_err_t ret = nvs_open(key,NVS_READWRITE,&handle);
if (ret == ESP_OK) {
sensor_t *s = esp_camera_sensor_get();
if (s != NULL) {
ret = nvs_set_blob(handle,CAMERA_SENSOR_NVS_KEY,&s->status,sizeof(camera_status_t));
if (ret == ESP_OK) {
uint8_t pf = s->pixformat;
ret = nvs_set_u8(handle,CAMERA_PIXFORMAT_NVS_KEY,pf);
}
return ret;
} else {
return ESP_ERR_CAMERA_NOT_DETECTED;
}
nvs_close(handle);
return ret;
} else {
return ret;
}
}
esp_err_t esp_camera_load_from_nvs(const char *key)
{
#if ESP_IDF_VERSION_MAJOR > 3
nvs_handle_t handle;
#else
nvs_handle handle;
#endif
uint8_t pf;
esp_err_t ret = nvs_open(key,NVS_READWRITE,&handle);
if (ret == ESP_OK) {
sensor_t *s = esp_camera_sensor_get();
camera_status_t st;
if (s != NULL) {
size_t size = sizeof(camera_status_t);
ret = nvs_get_blob(handle,CAMERA_SENSOR_NVS_KEY,&st,&size);
if (ret == ESP_OK) {
s->set_ae_level(s,st.ae_level);
s->set_aec2(s,st.aec2);
s->set_aec_value(s,st.aec_value);
s->set_agc_gain(s,st.agc_gain);
s->set_awb_gain(s,st.awb_gain);
s->set_bpc(s,st.bpc);
s->set_brightness(s,st.brightness);
s->set_colorbar(s,st.colorbar);
s->set_contrast(s,st.contrast);
s->set_dcw(s,st.dcw);
s->set_denoise(s,st.denoise);
s->set_exposure_ctrl(s,st.aec);
s->set_framesize(s,st.framesize);
s->set_gain_ctrl(s,st.agc);
s->set_gainceiling(s,st.gainceiling);
s->set_hmirror(s,st.hmirror);
s->set_lenc(s,st.lenc);
s->set_quality(s,st.quality);
s->set_raw_gma(s,st.raw_gma);
s->set_saturation(s,st.saturation);
s->set_sharpness(s,st.sharpness);
s->set_special_effect(s,st.special_effect);
s->set_vflip(s,st.vflip);
s->set_wb_mode(s,st.wb_mode);
s->set_whitebal(s,st.awb);
s->set_wpc(s,st.wpc);
}
ret = nvs_get_u8(handle,CAMERA_PIXFORMAT_NVS_KEY,&pf);
if (ret == ESP_OK) {
s->set_pixformat(s,pf);
}
} else {
return ESP_ERR_CAMERA_NOT_DETECTED;
}
nvs_close(handle);
return ret;
} else {
ESP_LOGW(TAG,"Error (%d) opening nvs key \"%s\"",ret,key);
return ret;
}
}

@ -38,7 +38,8 @@
.pixel_format = PIXFORMAT_JPEG,
.frame_size = FRAMESIZE_SVGA,
.jpeg_quality = 10,
.fb_count = 2
.fb_count = 2,
.grab_mode = CAMERA_GRAB_WHEN_EMPTY
};
esp_err_t camera_example_init(){
@ -74,6 +75,14 @@
extern "C" {
#endif
/**
* @brief Configuration structure for camera initialization
*/
typedef enum {
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 */
} camera_grab_mode_t;
/**
* @brief Configuration structure for camera initialization
*/
@ -95,7 +104,7 @@ typedef struct {
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) */
int xclk_freq_hz; /*!< Frequency of XCLK signal, in Hz. EXPERIMENTAL: Set to 16MHz on ESP32-S2 or ESP32-S3 to enable EDMA mode */
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 */
@ -105,6 +114,7 @@ typedef struct {
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_grab_mode_t grab_mode; /*!< When buffers should be filled */
} camera_config_t;
/**

@ -17,7 +17,11 @@
#if ESP_IDF_VERSION_MAJOR >= 4 // IDF 4+
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
#include "esp32/rom/tjpgd.h"
#else
#elif CONFIG_IDF_TARGET_ESP32S2
#include "tjpgd.h"
#elif CONFIG_IDF_TARGET_ESP32S3
#include "esp32s3/rom/tjpgd.h"
#else
#error Target CONFIG_IDF_TARGET is not supported
#endif
#else // ESP32 Before IDF 4.0

@ -22,6 +22,7 @@ extern "C" {
#include <stdint.h>
#include <stdbool.h>
#include "esp_camera.h"
#include "esp_jpg_decode.h"
typedef size_t (* jpg_out_cb)(void * arg, size_t index, const void* data, size_t len);
@ -120,6 +121,8 @@ bool frame2bmp(camera_fb_t * fb, uint8_t ** out, size_t * out_len);
*/
bool fmt2rgb888(const uint8_t *src_buf, size_t src_len, pixformat_t format, uint8_t * rgb_buf);
bool jpg2rgb565(const uint8_t *src, size_t src_len, uint8_t * out, jpg_scale_t scale);
#ifdef __cplusplus
}
#endif

@ -0,0 +1,26 @@
{
"name": "esp32-camera",
"version": "1.0.0",
"keywords": "esp32, camera, espressif, esp32-cam",
"description": "ESP32 compatible driver for OV2640, OV3660, OV5640, OV7670 and OV7725 image sensors.",
"repository": {
"type": "git",
"url": "https://github.com/espressif/esp32-camera"
},
"frameworks": "espidf",
"platforms": "*",
"build": {
"flags": [
"-Idriver/include",
"-Iconversions/include",
"-Idriver/private_include",
"-Iconversions/private_include",
"-Isensors/private_include",
"-Itarget/private_include",
"-fno-rtti"
],
"includeDir": ".",
"srcDir": ".",
"srcFilter": ["-<*>", "+<driver>", "+<conversions>", "+<sensors>"]
}
}

@ -0,0 +1,515 @@
// Copyright 2010-2020 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.
#include <stdio.h>
#include <string.h>
#include "soc/i2s_struct.h"
#include "esp_idf_version.h"
#if ESP_IDF_VERSION_MAJOR >= 4
#include "hal/gpio_ll.h"
#else
#include "rom/ets_sys.h"
#include "soc/gpio_periph.h"
#define esp_rom_delay_us ets_delay_us
static inline int gpio_ll_get_level(gpio_dev_t *hw, int gpio_num)
{
if (gpio_num < 32) {
return (hw->in >> gpio_num) & 0x1;
} else {
return (hw->in1.data >> (gpio_num - 32)) & 0x1;
}
}
#endif
#include "ll_cam.h"
#include "xclk.h"
#include "cam_hal.h"
static const char *TAG = "esp32 ll_cam";
#define I2S_ISR_ENABLE(i) {I2S0.int_clr.i = 1;I2S0.int_ena.i = 1;}
#define I2S_ISR_DISABLE(i) {I2S0.int_ena.i = 0;I2S0.int_clr.i = 1;}
typedef union {
struct {
uint32_t sample2:8;
uint32_t unused2:8;
uint32_t sample1:8;
uint32_t unused1:8;
};
uint32_t val;
} dma_elem_t;
typedef enum {
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 s2, 00 s2 00 s3, 00 s3 00 s4, ...
*/
SM_0A0B_0B0C = 0,
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 s2, 00 s3 00 s4, ...
*/
SM_0A0B_0C0D = 1,
/* camera sends byte sequence: s1, s2, s3, s4, ...
* fifo receives: 00 s1 00 00, 00 s2 00 00, 00 s3 00 00, ...
*/
SM_0A00_0B00 = 3,
} i2s_sampling_mode_t;
typedef size_t (*dma_filter_t)(uint8_t* dst, const uint8_t* src, size_t len);
static i2s_sampling_mode_t sampling_mode = SM_0A00_0B00;
static size_t ll_cam_bytes_per_sample(i2s_sampling_mode_t mode)
{
switch(mode) {
case SM_0A00_0B00:
return 4;
case SM_0A0B_0B0C:
return 4;
case SM_0A0B_0C0D:
return 2;
default:
assert(0 && "invalid sampling mode");
return 0;
}
}
static size_t IRAM_ATTR ll_cam_dma_filter_jpeg(uint8_t* dst, const uint8_t* src, size_t len)
{
const dma_elem_t* dma_el = (const dma_elem_t*)src;
size_t elements = len / sizeof(dma_elem_t);
size_t end = elements / 4;
// manually unrolling 4 iterations of the loop here
for (size_t i = 0; i < end; ++i) {
dst[0] = dma_el[0].sample1;
dst[1] = dma_el[1].sample1;
dst[2] = dma_el[2].sample1;
dst[3] = dma_el[3].sample1;
dma_el += 4;
dst += 4;
}
return elements;
}
static size_t IRAM_ATTR ll_cam_dma_filter_grayscale(uint8_t* dst, const uint8_t* src, size_t len)
{
const dma_elem_t* dma_el = (const dma_elem_t*)src;
size_t elements = len / sizeof(dma_elem_t);
size_t end = elements / 4;
for (size_t i = 0; i < end; ++i) {
// manually unrolling 4 iterations of the loop here
dst[0] = dma_el[0].sample1;
dst[1] = dma_el[1].sample1;
dst[2] = dma_el[2].sample1;
dst[3] = dma_el[3].sample1;
dma_el += 4;
dst += 4;
}
return elements;
}
static size_t IRAM_ATTR ll_cam_dma_filter_grayscale_highspeed(uint8_t* dst, const uint8_t* src, size_t len)
{
const dma_elem_t* dma_el = (const dma_elem_t*)src;
size_t elements = len / sizeof(dma_elem_t);
size_t end = elements / 8;
for (size_t i = 0; i < end; ++i) {
// manually unrolling 4 iterations of the loop here
dst[0] = dma_el[0].sample1;
dst[1] = dma_el[2].sample1;
dst[2] = dma_el[4].sample1;
dst[3] = dma_el[6].sample1;
dma_el += 8;
dst += 4;
}
// the final sample of a line in SM_0A0B_0B0C sampling mode needs special handling
if ((elements & 0x7) != 0) {
dst[0] = dma_el[0].sample1;
dst[1] = dma_el[2].sample1;
elements += 1;
}
return elements / 2;
}
static size_t IRAM_ATTR ll_cam_dma_filter_yuyv(uint8_t* dst, const uint8_t* src, size_t len)
{
const dma_elem_t* dma_el = (const dma_elem_t*)src;
size_t elements = len / sizeof(dma_elem_t);
size_t end = elements / 4;
for (size_t i = 0; i < end; ++i) {
dst[0] = dma_el[0].sample1;//y0
dst[1] = dma_el[0].sample2;//u
dst[2] = dma_el[1].sample1;//y1
dst[3] = dma_el[1].sample2;//v
dst[4] = dma_el[2].sample1;//y0
dst[5] = dma_el[2].sample2;//u
dst[6] = dma_el[3].sample1;//y1
dst[7] = dma_el[3].sample2;//v
dma_el += 4;
dst += 8;
}
return elements * 2;
}
static size_t IRAM_ATTR ll_cam_dma_filter_yuyv_highspeed(uint8_t* dst, const uint8_t* src, size_t len)
{
const dma_elem_t* dma_el = (const dma_elem_t*)src;
size_t elements = len / sizeof(dma_elem_t);
size_t end = elements / 8;
for (size_t i = 0; i < end; ++i) {
dst[0] = dma_el[0].sample1;//y0
dst[1] = dma_el[1].sample1;//u
dst[2] = dma_el[2].sample1;//y1
dst[3] = dma_el[3].sample1;//v
dst[4] = dma_el[4].sample1;//y0
dst[5] = dma_el[5].sample1;//u
dst[6] = dma_el[6].sample1;//y1
dst[7] = dma_el[7].sample1;//v
dma_el += 8;
dst += 8;
}
if ((elements & 0x7) != 0) {
dst[0] = dma_el[0].sample1;//y0
dst[1] = dma_el[1].sample1;//u
dst[2] = dma_el[2].sample1;//y1
dst[3] = dma_el[2].sample2;//v
elements += 4;
}
return elements;
}
static void IRAM_ATTR ll_cam_vsync_isr(void *arg)
{
//DBG_PIN_SET(1);
cam_obj_t *cam = (cam_obj_t *)arg;
BaseType_t HPTaskAwoken = pdFALSE;
// filter
esp_rom_delay_us(1);
if (gpio_ll_get_level(&GPIO, cam->vsync_pin) == !cam->vsync_invert) {
ll_cam_send_event(cam, CAM_VSYNC_EVENT, &HPTaskAwoken);
if (HPTaskAwoken == pdTRUE) {
portYIELD_FROM_ISR();
}
}
//DBG_PIN_SET(0);
}
static void IRAM_ATTR ll_cam_dma_isr(void *arg)
{
//DBG_PIN_SET(1);
cam_obj_t *cam = (cam_obj_t *)arg;
BaseType_t HPTaskAwoken = pdFALSE;
typeof(I2S0.int_st) status = I2S0.int_st;
if (status.val == 0) {
return;
}
I2S0.int_clr.val = status.val;
if (status.in_suc_eof) {
ll_cam_send_event(cam, CAM_IN_SUC_EOF_EVENT, &HPTaskAwoken);
}
if (HPTaskAwoken == pdTRUE) {
portYIELD_FROM_ISR();
}
//DBG_PIN_SET(0);
}
bool ll_cam_stop(cam_obj_t *cam)
{
I2S0.conf.rx_start = 0;
I2S_ISR_DISABLE(in_suc_eof);
I2S0.in_link.stop = 1;
return true;
}
bool ll_cam_start(cam_obj_t *cam, int frame_pos)
{
I2S0.conf.rx_start = 0;
I2S_ISR_ENABLE(in_suc_eof);
I2S0.conf.rx_reset = 1;
I2S0.conf.rx_reset = 0;
I2S0.conf.rx_fifo_reset = 1;
I2S0.conf.rx_fifo_reset = 0;
I2S0.lc_conf.in_rst = 1;
I2S0.lc_conf.in_rst = 0;
I2S0.lc_conf.ahbm_fifo_rst = 1;
I2S0.lc_conf.ahbm_fifo_rst = 0;
I2S0.lc_conf.ahbm_rst = 1;
I2S0.lc_conf.ahbm_rst = 0;
I2S0.rx_eof_num = cam->dma_half_buffer_size / sizeof(dma_elem_t);
I2S0.in_link.addr = ((uint32_t)&cam->dma[0]) & 0xfffff;
I2S0.in_link.start = 1;
I2S0.conf.rx_start = 1;
return true;
}
esp_err_t ll_cam_config(cam_obj_t *cam, const camera_config_t *config)
{
// Enable and configure I2S peripheral
periph_module_enable(PERIPH_I2S0_MODULE);
I2S0.conf.rx_reset = 1;
I2S0.conf.rx_reset = 0;
I2S0.conf.rx_fifo_reset = 1;
I2S0.conf.rx_fifo_reset = 0;
I2S0.lc_conf.in_rst = 1;
I2S0.lc_conf.in_rst = 0;
I2S0.lc_conf.ahbm_fifo_rst = 1;
I2S0.lc_conf.ahbm_fifo_rst = 0;
I2S0.lc_conf.ahbm_rst = 1;
I2S0.lc_conf.ahbm_rst = 0;
I2S0.conf.rx_slave_mod = 1;
I2S0.conf.rx_right_first = 0;
I2S0.conf.rx_msb_right = 0;
I2S0.conf.rx_msb_shift = 0;
I2S0.conf.rx_mono = 0;
I2S0.conf.rx_short_sync = 0;
I2S0.conf2.lcd_en = 1;
I2S0.conf2.camera_en = 1;
// Configure clock divider
I2S0.clkm_conf.clkm_div_a = 0;
I2S0.clkm_conf.clkm_div_b = 0;
I2S0.clkm_conf.clkm_div_num = 2;
I2S0.fifo_conf.dscr_en = 1;
I2S0.fifo_conf.rx_fifo_mod = sampling_mode;
I2S0.fifo_conf.rx_fifo_mod_force_en = 1;
I2S0.conf_chan.rx_chan_mod = 1;
I2S0.sample_rate_conf.rx_bits_mod = 0;
I2S0.timing.val = 0;
I2S0.timing.rx_dsync_sw = 1;
return ESP_OK;
}
void ll_cam_vsync_intr_enable(cam_obj_t *cam, bool en)
{
if (en) {
gpio_intr_enable(cam->vsync_pin);
} else {
gpio_intr_disable(cam->vsync_pin);
}
}
esp_err_t ll_cam_set_pin(cam_obj_t *cam, const camera_config_t *config)
{
gpio_config_t io_conf = {0};
io_conf.intr_type = cam->vsync_invert ? GPIO_PIN_INTR_NEGEDGE : GPIO_PIN_INTR_POSEDGE;
io_conf.pin_bit_mask = 1ULL << config->pin_vsync;
io_conf.mode = GPIO_MODE_INPUT;
io_conf.pull_up_en = 1;
io_conf.pull_down_en = 0;
gpio_config(&io_conf);
gpio_install_isr_service(ESP_INTR_FLAG_LOWMED | ESP_INTR_FLAG_IRAM);
gpio_isr_handler_add(config->pin_vsync, ll_cam_vsync_isr, cam);
gpio_intr_disable(config->pin_vsync);
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[config->pin_pclk], PIN_FUNC_GPIO);
gpio_set_direction(config->pin_pclk, GPIO_MODE_INPUT);
gpio_set_pull_mode(config->pin_pclk, GPIO_FLOATING);
gpio_matrix_in(config->pin_pclk, I2S0I_WS_IN_IDX, false);
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[config->pin_vsync], PIN_FUNC_GPIO);
gpio_set_direction(config->pin_vsync, GPIO_MODE_INPUT);
gpio_set_pull_mode(config->pin_vsync, GPIO_FLOATING);
gpio_matrix_in(config->pin_vsync, I2S0I_V_SYNC_IDX, false);
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[config->pin_href], PIN_FUNC_GPIO);
gpio_set_direction(config->pin_href, GPIO_MODE_INPUT);
gpio_set_pull_mode(config->pin_href, GPIO_FLOATING);
gpio_matrix_in(config->pin_href, I2S0I_H_SYNC_IDX, false);
int data_pins[8] = {
config->pin_d0, config->pin_d1, config->pin_d2, config->pin_d3, config->pin_d4, config->pin_d5, config->pin_d6, config->pin_d7,
};
for (int i = 0; i < 8; i++) {
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[data_pins[i]], PIN_FUNC_GPIO);
gpio_set_direction(data_pins[i], GPIO_MODE_INPUT);
gpio_set_pull_mode(data_pins[i], GPIO_FLOATING);
gpio_matrix_in(data_pins[i], I2S0I_DATA_IN0_IDX + i, false);
}
gpio_matrix_in(0x38, I2S0I_H_ENABLE_IDX, false);
return ESP_OK;
}
esp_err_t ll_cam_init_isr(cam_obj_t *cam)
{
return esp_intr_alloc(ETS_I2S0_INTR_SOURCE, ESP_INTR_FLAG_LOWMED | ESP_INTR_FLAG_IRAM, ll_cam_dma_isr, cam, &cam->cam_intr_handle);
}
void ll_cam_do_vsync(cam_obj_t *cam)
{
}
uint8_t ll_cam_get_dma_align(cam_obj_t *cam)
{
return 0;
}
static bool ll_cam_calc_rgb_dma(cam_obj_t *cam){
size_t dma_half_buffer_max = 16 * 1024 / cam->dma_bytes_per_item;
size_t dma_buffer_max = 2 * dma_half_buffer_max;
size_t node_max = LCD_CAM_DMA_NODE_BUFFER_MAX_SIZE / cam->dma_bytes_per_item;
size_t line_width = cam->width * cam->in_bytes_per_pixel;
size_t image_size = cam->height * line_width;
if (image_size > (2 * 1024 * 1024) || (line_width > dma_half_buffer_max)) {
ESP_LOGE(TAG, "Resolution too high");
return 0;
}
size_t node_size = node_max;
size_t nodes_per_line = 1;
size_t lines_per_node = 1;
size_t lines_per_half_buffer = 1;
size_t dma_half_buffer_min = node_max;
size_t dma_half_buffer = dma_half_buffer_max;
size_t dma_buffer_size = dma_buffer_max;
// Calculate DMA Node Size so that it's divisable by or divisor of the line width
if(line_width >= node_max){
// One or more nodes will be requied for one line
for(size_t i = node_max; i > 0; i=i-1){
if ((line_width % i) == 0) {
node_size = i;
nodes_per_line = line_width / node_size;
break;
}
}
} else {
// One or more lines can fit into one node
for(size_t i = node_max; i > 0; i=i-1){
if ((i % line_width) == 0) {
node_size = i;
lines_per_node = node_size / line_width;
while((cam->height % lines_per_node) != 0){
lines_per_node = lines_per_node - 1;
node_size = lines_per_node * line_width;
}
break;
}
}
}
// Calculate minimum EOF size = max(mode_size, line_size)
dma_half_buffer_min = node_size * nodes_per_line;
// Calculate max EOF size divisable by node size
dma_half_buffer = (dma_half_buffer_max / dma_half_buffer_min) * dma_half_buffer_min;
// Adjust EOF size so that height will be divisable by the number of lines in each EOF
lines_per_half_buffer = dma_half_buffer / line_width;
while((cam->height % lines_per_half_buffer) != 0){
dma_half_buffer = dma_half_buffer - dma_half_buffer_min;
lines_per_half_buffer = dma_half_buffer / line_width;
}
// Calculate DMA size
dma_buffer_size =(dma_buffer_max / dma_half_buffer) * dma_half_buffer;
ESP_LOGI(TAG, "node_size: %4u, nodes_per_line: %u, lines_per_node: %u, dma_half_buffer_min: %5u, dma_half_buffer: %5u, lines_per_half_buffer: %2u, dma_buffer_size: %5u, image_size: %u",
node_size * cam->dma_bytes_per_item, nodes_per_line, lines_per_node, dma_half_buffer_min * cam->dma_bytes_per_item, dma_half_buffer * cam->dma_bytes_per_item, lines_per_half_buffer, dma_buffer_size * cam->dma_bytes_per_item, image_size);
cam->dma_buffer_size = dma_buffer_size * cam->dma_bytes_per_item;
cam->dma_half_buffer_size = dma_half_buffer * cam->dma_bytes_per_item;
cam->dma_node_buffer_size = node_size * cam->dma_bytes_per_item;
cam->dma_half_buffer_cnt = cam->dma_buffer_size / cam->dma_half_buffer_size;
return 1;
}
bool ll_cam_dma_sizes(cam_obj_t *cam)
{
cam->dma_bytes_per_item = ll_cam_bytes_per_sample(sampling_mode);
if (cam->jpeg_mode) {
cam->dma_half_buffer_cnt = 8;
cam->dma_node_buffer_size = 2048;
cam->dma_half_buffer_size = cam->dma_node_buffer_size * 2;
cam->dma_buffer_size = cam->dma_half_buffer_cnt * cam->dma_half_buffer_size;
} else {
return ll_cam_calc_rgb_dma(cam);
}
return 1;
}
static dma_filter_t dma_filter = ll_cam_dma_filter_jpeg;
size_t IRAM_ATTR ll_cam_memcpy(cam_obj_t *cam, uint8_t *out, const uint8_t *in, size_t len)
{
//DBG_PIN_SET(1);
size_t r = dma_filter(out, in, len);
//DBG_PIN_SET(0);
return r;
}
esp_err_t ll_cam_set_sample_mode(cam_obj_t *cam, pixformat_t pix_format, uint32_t xclk_freq_hz, uint8_t sensor_pid)
{
if (pix_format == PIXFORMAT_GRAYSCALE) {
if (sensor_pid == OV3660_PID || sensor_pid == OV5640_PID || sensor_pid == NT99141_PID) {
if (xclk_freq_hz > 10000000) {
sampling_mode = SM_0A00_0B00;
dma_filter = ll_cam_dma_filter_yuyv_highspeed;
} else {
sampling_mode = SM_0A0B_0C0D;
dma_filter = ll_cam_dma_filter_yuyv;
}
cam->in_bytes_per_pixel = 1; // camera sends Y8
} else {
if (xclk_freq_hz > 10000000 && sensor_pid != OV7725_PID) {
sampling_mode = SM_0A00_0B00;
dma_filter = ll_cam_dma_filter_grayscale_highspeed;
} else {
sampling_mode = SM_0A0B_0C0D;
dma_filter = ll_cam_dma_filter_grayscale;
}
cam->in_bytes_per_pixel = 2; // camera sends YU/YV
}
cam->fb_bytes_per_pixel = 1; // frame buffer stores Y8
} else if (pix_format == PIXFORMAT_YUV422 || pix_format == PIXFORMAT_RGB565) {
if (xclk_freq_hz > 10000000 && sensor_pid != OV7725_PID) {
if (sensor_pid == OV7670_PID) {
sampling_mode = SM_0A0B_0B0C;
} else {
sampling_mode = SM_0A00_0B00;
}
dma_filter = ll_cam_dma_filter_yuyv_highspeed;
} else {
sampling_mode = SM_0A0B_0C0D;
dma_filter = ll_cam_dma_filter_yuyv;
}
cam->in_bytes_per_pixel = 2; // camera sends YU/YV
cam->fb_bytes_per_pixel = 2; // frame buffer stores YU/YV/RGB565
} else if (pix_format == PIXFORMAT_JPEG) {
if (sensor_pid != OV2640_PID && sensor_pid != OV3660_PID && sensor_pid != OV5640_PID && sensor_pid != NT99141_PID) {
ESP_LOGE(TAG, "JPEG format is not supported on this sensor");
return ESP_ERR_NOT_SUPPORTED;
}
cam->in_bytes_per_pixel = 1;
cam->fb_bytes_per_pixel = 1;
dma_filter = ll_cam_dma_filter_jpeg;
sampling_mode = SM_0A00_0B00;
} else {
ESP_LOGE(TAG, "Requested format is not supported");
return ESP_ERR_NOT_SUPPORTED;
}
I2S0.fifo_conf.rx_fifo_mod = sampling_mode;
return ESP_OK;
}

@ -0,0 +1,136 @@
// Copyright 2010-2020 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.
#pragma once
#include <stdint.h>
#include "sdkconfig.h"
#if CONFIG_IDF_TARGET_ESP32
#if ESP_IDF_VERSION_MAJOR >= 4
#include "esp32/rom/lldesc.h"
#else
#include "rom/lldesc.h"
#endif
#elif CONFIG_IDF_TARGET_ESP32S2
#include "esp32s2/rom/lldesc.h"
#elif CONFIG_IDF_TARGET_ESP32S3
#include "esp32s3/rom/lldesc.h"
#endif
#include "esp_log.h"
#include "esp_camera.h"
#include "camera_common.h"
#include "freertos/FreeRTOS.h"
#include "freertos/queue.h"
#include "freertos/task.h"
#include "freertos/semphr.h"
#define CAMERA_DBG_PIN_ENABLE 0
#if CAMERA_DBG_PIN_ENABLE
#if CONFIG_IDF_TARGET_ESP32
#define DBG_PIN_NUM 26
#else
#define DBG_PIN_NUM 7
#endif
#include "hal/gpio_ll.h"
#define DBG_PIN_SET(v) gpio_ll_set_level(&GPIO, DBG_PIN_NUM, v)
#else
#define DBG_PIN_SET(v)
#endif
#define CAM_CHECK(a, str, ret) if (!(a)) { \
ESP_LOGE(TAG,"%s(%d): %s", __FUNCTION__, __LINE__, str); \
return (ret); \
}
#define CAM_CHECK_GOTO(a, str, lab) if (!(a)) { \
ESP_LOGE(TAG,"%s(%d): %s", __FUNCTION__, __LINE__, str); \
goto lab; \
}
#define LCD_CAM_DMA_NODE_BUFFER_MAX_SIZE (4092)
typedef enum {
CAM_IN_SUC_EOF_EVENT = 0,
CAM_VSYNC_EVENT
} cam_event_t;
typedef enum {
CAM_STATE_IDLE = 0,
CAM_STATE_READ_BUF = 1,
} cam_state_t;
typedef struct {
camera_fb_t fb;
uint8_t en;
//for RGB/YUV modes
lldesc_t *dma;
size_t fb_offset;
} cam_frame_t;
typedef struct {
uint32_t dma_bytes_per_item;
uint32_t dma_buffer_size;
uint32_t dma_half_buffer_size;
uint32_t dma_half_buffer_cnt;
uint32_t dma_node_buffer_size;
uint32_t dma_node_cnt;
uint32_t frame_copy_cnt;
//for JPEG mode
lldesc_t *dma;
uint8_t *dma_buffer;
cam_frame_t *frames;
QueueHandle_t event_queue;
QueueHandle_t frame_buffer_queue;
TaskHandle_t task_handle;
intr_handle_t cam_intr_handle;
uint8_t dma_num;//ESP32-S3
intr_handle_t dma_intr_handle;//ESP32-S3
uint8_t jpeg_mode;
uint8_t vsync_pin;
uint8_t vsync_invert;
uint32_t frame_cnt;
uint32_t recv_size;
bool swap_data;
bool psram_mode;
//for RGB/YUV modes
uint16_t width;
uint16_t height;
uint8_t in_bytes_per_pixel;
uint8_t fb_bytes_per_pixel;
uint32_t fb_size;
cam_state_t state;
} cam_obj_t;
bool ll_cam_stop(cam_obj_t *cam);
bool ll_cam_start(cam_obj_t *cam, int frame_pos);
esp_err_t ll_cam_config(cam_obj_t *cam, const camera_config_t *config);
void ll_cam_vsync_intr_enable(cam_obj_t *cam, bool en);
esp_err_t ll_cam_set_pin(cam_obj_t *cam, const camera_config_t *config);
esp_err_t ll_cam_init_isr(cam_obj_t *cam);
void ll_cam_do_vsync(cam_obj_t *cam);
uint8_t ll_cam_get_dma_align(cam_obj_t *cam);
bool ll_cam_dma_sizes(cam_obj_t *cam);
size_t ll_cam_memcpy(cam_obj_t *cam, uint8_t *out, const uint8_t *in, size_t len);
esp_err_t ll_cam_set_sample_mode(cam_obj_t *cam, pixformat_t pix_format, uint32_t xclk_freq_hz, uint8_t sensor_pid);
// implemented in cam_hal
void ll_cam_send_event(cam_obj_t *cam, cam_event_t cam_event, BaseType_t * HPTaskAwoken);

@ -144,28 +144,6 @@ static int write_addr_reg(uint8_t slv_addr, const uint16_t reg, uint16_t x_value
#define write_reg_bits(slv_addr, reg, mask, enable) set_reg_bits(slv_addr, reg, 0, mask, enable?mask:0)
static int calc_sysclk(int xclk, bool pll_bypass, int pll_multiplier, int pll_sys_div, int pll_pre_div, bool pll_root_2x, int pll_seld5, bool pclk_manual, int pclk_div)
{
const int pll_pre_div2x_map[] = { 2, 3, 4, 6 };//values are multiplied by two to avoid floats
const int pll_seld52x_map[] = { 2, 2, 4, 5 };
if (!pll_sys_div) {
pll_sys_div = 1;
}
int pll_pre_div2x = pll_pre_div2x_map[pll_pre_div];
int pll_root_div = pll_root_2x ? 2 : 1;
int pll_seld52x = pll_seld52x_map[pll_seld5];
int VCO = (xclk / 1000) * pll_multiplier * pll_root_div * 2 / pll_pre_div2x;
int PLLCLK = pll_bypass ? (xclk) : (VCO * 1000 * 2 / pll_sys_div / pll_seld52x);
int PCLK = PLLCLK / 2 / ((pclk_manual && pclk_div) ? pclk_div : 1);
int SYSCLK = PLLCLK / 4;
ESP_LOGD(TAG, "Calculated VCO: %d Hz, PLLCLK: %d Hz, SYSCLK: %d Hz, PCLK: %d Hz", VCO * 1000, PLLCLK, SYSCLK, PCLK);
return SYSCLK;
}
static int set_pll(sensor_t *sensor, bool bypass, uint8_t multiplier, uint8_t sys_div, uint8_t pre_div, bool root_2x, uint8_t seld5, bool pclk_manual, uint8_t pclk_div)
{
return -1;
@ -309,7 +287,7 @@ static int set_framesize(sensor_t *sensor, framesize_t framesize)
ret = write_regs(sensor->slv_addr, sensor_framesize_VGA);
}
return 0;
return ret;
}
static int set_hmirror(sensor_t *sensor, int enable)
@ -682,7 +660,6 @@ static int set_brightness(sensor_t *sensor, int level)
{
int ret = 0;
uint8_t value = 0;
bool negative = false;
switch (level) {
case 3:
@ -699,17 +676,14 @@ static int set_brightness(sensor_t *sensor, int level)
case -1:
value = 0x78;
negative = true;
break;
case -2:
value = 0x70;
negative = true;
break;
case -3:
value = 0x60;
negative = true;
break;
default: // 0
@ -730,7 +704,6 @@ static int set_contrast(sensor_t *sensor, int level)
{
int ret = 0;
uint8_t value1 = 0, value2 = 0 ;
bool negative = false;
switch (level) {
case 3:

@ -157,26 +157,40 @@ static int set_window(sensor_t *sensor, ov2640_sensor_mode_t mode, int offset_x,
{0, 0}
};
c.pclk_auto = 0;
c.pclk_div = 8;
c.clk_2x = 0;
c.clk_div = 0;
if(sensor->pixformat != PIXFORMAT_JPEG){
c.pclk_auto = 1;
if (sensor->pixformat == PIXFORMAT_JPEG) {
c.clk_2x = 0;
c.clk_div = 0;
c.pclk_auto = 0;
c.pclk_div = 8;
if(mode == OV2640_MODE_UXGA) {
c.pclk_div = 12;
}
// if (sensor->xclk_freq_hz == 16000000) {
// c.pclk_div = c.pclk_div / 2;
// }
} else {
#if CONFIG_IDF_TARGET_ESP32
c.clk_2x = 0;
#else
c.clk_2x = 1;
#endif
c.clk_div = 7;
c.pclk_auto = 1;
c.pclk_div = 8;
if (mode == OV2640_MODE_CIF) {
c.clk_div = 3;
} else if(mode == OV2640_MODE_UXGA) {
c.pclk_div = 12;
}
}
ESP_LOGI(TAG, "Set PLL: clk_2x: %u, clk_div: %u, pclk_auto: %u, pclk_div: %u", c.clk_2x, c.clk_div, c.pclk_auto, c.pclk_div);
if (mode == OV2640_MODE_CIF) {
regs = ov2640_settings_to_cif;
if(sensor->pixformat != PIXFORMAT_JPEG){
c.clk_div = 3;
}
} else if (mode == OV2640_MODE_SVGA) {
regs = ov2640_settings_to_svga;
} else {
regs = ov2640_settings_to_uxga;
c.pclk_div = 12;
}
WRITE_REG_OR_RETURN(BANK_DSP, R_BYPASS, R_BYPASS_DSP_BYPAS);

@ -142,7 +142,7 @@ static int calc_sysclk(int xclk, bool pll_bypass, int pll_multiplier, int pll_sy
int PCLK = PLLCLK / 2 / ((pclk_manual && pclk_div)?pclk_div:1);
int SYSCLK = PLLCLK / 4;
ESP_LOGD(TAG, "Calculated VCO: %d Hz, PLLCLK: %d Hz, SYSCLK: %d Hz, PCLK: %d Hz", VCO*1000, PLLCLK, SYSCLK, PCLK);
ESP_LOGI(TAG, "Calculated VCO: %d Hz, PLLCLK: %d Hz, SYSCLK: %d Hz, PCLK: %d Hz", VCO*1000, PLLCLK, SYSCLK, PCLK);
return SYSCLK;
}
@ -310,13 +310,13 @@ static int set_image_options(sensor_t *sensor)
static int set_framesize(sensor_t *sensor, framesize_t framesize)
{
int ret = 0;
framesize_t old_framesize = sensor->status.framesize;
sensor->status.framesize = framesize;
if(framesize > FRAMESIZE_QXGA){
ESP_LOGE(TAG, "Invalid framesize: %u", framesize);
return -1;
ESP_LOGW(TAG, "Invalid framesize: %u", framesize);
framesize = FRAMESIZE_QXGA;
}
framesize_t old_framesize = sensor->status.framesize;
sensor->status.framesize = framesize;
uint16_t w = resolution[framesize].width;
uint16_t h = resolution[framesize].height;
aspect_ratio_t ratio = resolution[sensor->status.framesize].aspect_ratio;
@ -355,7 +355,7 @@ static int set_framesize(sensor_t *sensor, framesize_t framesize)
}
if (sensor->pixformat == PIXFORMAT_JPEG) {
if (framesize == FRAMESIZE_QXGA) {
if (framesize == FRAMESIZE_QXGA || sensor->xclk_freq_hz == 16000000) {
//40MHz SYSCLK and 10MHz PCLK
ret = set_pll(sensor, false, 24, 1, 3, false, 0, true, 8);
} else {
@ -363,12 +363,16 @@ static int set_framesize(sensor_t *sensor, framesize_t framesize)
ret = set_pll(sensor, false, 30, 1, 3, false, 0, true, 10);
}
} else {
if (framesize > FRAMESIZE_CIF) {
//10MHz SYSCLK and 10MHz PCLK (6.19 FPS)
ret = set_pll(sensor, false, 2, 1, 0, false, 0, true, 2);
//tuned for 16MHz XCLK and 8MHz PCLK
if (framesize > FRAMESIZE_HVGA) {
//8MHz SYSCLK and 8MHz PCLK (4.44 FPS)
ret = set_pll(sensor, false, 4, 1, 0, false, 2, true, 2);
} else if (framesize >= FRAMESIZE_QVGA) {
//16MHz SYSCLK and 8MHz PCLK (10.25 FPS)
ret = set_pll(sensor, false, 8, 1, 0, false, 2, true, 4);
} else {
//25MHz SYSCLK and 10MHz PCLK (15.45 FPS)
ret = set_pll(sensor, false, 5, 1, 0, false, 0, true, 5);
//32MHz SYSCLK and 8MHz PCLK (17.77 FPS)
ret = set_pll(sensor, false, 8, 1, 0, false, 0, true, 8);
}
}

@ -196,7 +196,7 @@ static int calc_sysclk(int xclk, bool pll_bypass, int pll_multiplier, int pll_sy
unsigned int SYSCLK = PLL_CLK / 4;
ESP_LOGD(TAG, "Calculated XVCLK: %d Hz, REFIN: %u Hz, VCO: %u Hz, PLL_CLK: %u Hz, SYSCLK: %u Hz, PCLK: %u Hz", xclk, REFIN, VCO, PLL_CLK, SYSCLK, PCLK);
ESP_LOGI(TAG, "Calculated XVCLK: %d Hz, REFIN: %u Hz, VCO: %u Hz, PLL_CLK: %u Hz, SYSCLK: %u Hz, PCLK: %u Hz", xclk, REFIN, VCO, PLL_CLK, SYSCLK, PCLK);
return SYSCLK;
}
@ -209,6 +209,7 @@ static int set_pll(sensor_t *sensor, bool bypass, uint8_t multiplier, uint8_t sy
if(multiplier > 127){
multiplier &= 0xFE;//only even integers above 127
}
ESP_LOGI(TAG, "Set PLL: bypass: %u, multiplier: %u, sys_div: %u, pre_div: %u, root_2x: %u, pclk_root_div: %u, pclk_manual: %u, pclk_div: %u", bypass, multiplier, sys_div, pre_div, root_2x, pclk_root_div, pclk_manual, pclk_div);
calc_sysclk(sensor->xclk_freq_hz, bypass, multiplier, sys_div, pre_div, root_2x, pclk_root_div, pclk_manual, pclk_div);
@ -432,14 +433,22 @@ static int set_framesize(sensor_t *sensor, framesize_t framesize)
if (sensor->pixformat == PIXFORMAT_JPEG) {
//10MHz PCLK
uint8_t sys_mul = 200;
if(framesize < FRAMESIZE_QVGA){
if(framesize < FRAMESIZE_QVGA || sensor->xclk_freq_hz == 16000000){
sys_mul = 160;
} else if(framesize < FRAMESIZE_XGA){
sys_mul = 180;
}
ret = set_pll(sensor, false, sys_mul, 4, 2, false, 2, true, 4);
//Set PLL: bypass: 0, multiplier: sys_mul, sys_div: 4, pre_div: 2, root_2x: 0, pclk_root_div: 2, pclk_manual: 1, pclk_div: 4
} else {
ret = set_pll(sensor, false, 10, 1, 1, false, 1, true, 4);
//ret = set_pll(sensor, false, 8, 1, 1, false, 1, true, 4);
if (framesize > FRAMESIZE_HVGA) {
ret = set_pll(sensor, false, 10, 1, 2, false, 1, true, 2);
} else if (framesize >= FRAMESIZE_QVGA) {
ret = set_pll(sensor, false, 8, 1, 1, false, 1, true, 4);
} else {
ret = set_pll(sensor, false, 20, 1, 1, false, 1, true, 8);
}
}
if (ret == 0) {

@ -11,6 +11,7 @@
#include <freertos/FreeRTOS.h>
#include <freertos/task.h>
#include "sccb.h"
#include "sensor.h"
#include <stdio.h>
#include "sdkconfig.h"
#if defined(ARDUINO_ARCH_ESP32) && defined(CONFIG_ARDUHAL_ESP_LOG)
@ -36,12 +37,10 @@ const int SCCB_I2C_PORT = 1;
#else
const int SCCB_I2C_PORT = 0;
#endif
static uint8_t ESP_SLAVE_ADDR = 0x3c;
int SCCB_Init(int pin_sda, int pin_scl)
{
ESP_LOGI(TAG, "pin_sda %d pin_scl %d\n", pin_sda, pin_scl);
//log_i("SCCB_Init start");
ESP_LOGI(TAG, "pin_sda %d pin_scl %d", pin_sda, pin_scl);
i2c_config_t conf;
memset(&conf, 0, sizeof(i2c_config_t));
conf.mode = I2C_MODE_MASTER;
@ -56,10 +55,30 @@ int SCCB_Init(int pin_sda, int pin_scl)
return 0;
}
uint8_t SCCB_Probe()
int SCCB_Deinit(void)
{
return i2c_driver_delete(SCCB_I2C_PORT);
}
uint8_t SCCB_Probe(void)
{
uint8_t slave_addr = 0x0;
while(slave_addr < 0x7f) {
// for (size_t i = 1; i < 0x80; i++) {
// i2c_cmd_handle_t cmd = i2c_cmd_link_create();
// i2c_master_start(cmd);
// i2c_master_write_byte(cmd, ( i << 1 ) | WRITE_BIT, ACK_CHECK_EN);
// i2c_master_stop(cmd);
// esp_err_t ret = i2c_master_cmd_begin(SCCB_I2C_PORT, cmd, 1000 / portTICK_RATE_MS);
// i2c_cmd_link_delete(cmd);
// if( ret == ESP_OK) {
// ESP_LOGW(TAG, "Found I2C Device at 0x%02X", i);
// }
// }
for (size_t i = 0; i < CAMERA_MODEL_MAX; i++) {
if (slave_addr == camera_sensor[i].sccb_addr) {
continue;
}
slave_addr = camera_sensor[i].sccb_addr;
i2c_cmd_handle_t cmd = i2c_cmd_link_create();
i2c_master_start(cmd);
i2c_master_write_byte(cmd, ( slave_addr << 1 ) | WRITE_BIT, ACK_CHECK_EN);
@ -67,12 +86,10 @@ uint8_t SCCB_Probe()
esp_err_t ret = i2c_master_cmd_begin(SCCB_I2C_PORT, cmd, 1000 / portTICK_RATE_MS);
i2c_cmd_link_delete(cmd);
if( ret == ESP_OK) {
ESP_SLAVE_ADDR = slave_addr;
return ESP_SLAVE_ADDR;
return slave_addr;
}
slave_addr++;
}
return ESP_SLAVE_ADDR;
return 0;
}
uint8_t SCCB_Read(uint8_t slv_addr, uint8_t reg)

@ -10,6 +10,7 @@
#define __SCCB_H__
#include <stdint.h>
int SCCB_Init(int pin_sda, int pin_scl);
int SCCB_Deinit(void);
uint8_t SCCB_Probe();
uint8_t SCCB_Read(uint8_t slv_addr, uint8_t reg);
uint8_t SCCB_Write(uint8_t slv_addr, uint8_t reg, uint8_t data);

@ -1,5 +1,14 @@
#include "sensor.h"
const camera_sensor_info_t camera_sensor[CAMERA_MODEL_MAX] = {
{CAMERA_OV7725, OV7725_SCCB_ADDR, OV7725_PID, FRAMESIZE_VGA},
{CAMERA_OV2640, OV2640_SCCB_ADDR, OV2640_PID, FRAMESIZE_UXGA},
{CAMERA_OV3660, OV3660_SCCB_ADDR, OV3660_PID, FRAMESIZE_QXGA},
{CAMERA_OV5640, OV5640_SCCB_ADDR, OV5640_PID, FRAMESIZE_QSXGA},
{CAMERA_OV7670, OV7670_SCCB_ADDR, OV7670_PID, FRAMESIZE_VGA},
{CAMERA_NT99141, NT99141_SCCB_ADDR, NT99141_PID, FRAMESIZE_HD},
};
const resolution_info_t resolution[FRAMESIZE_INVALID] = {
{ 96, 96, ASPECT_RATIO_1X1 }, /* 96x96 */
{ 160, 120, ASPECT_RATIO_4X3 }, /* QQVGA */

@ -11,13 +11,45 @@
#include <stdint.h>
#include <stdbool.h>
#define NT99141_PID (0x14)
#define OV9650_PID (0x96)
#define OV7725_PID (0x77)
#define OV2640_PID (0x26)
#define OV3660_PID (0x36)
#define OV5640_PID (0x56)
#define OV7670_PID (0x76)
// Chip ID Registers
#define REG_PID 0x0A
#define REG_VER 0x0B
#define REG_MIDH 0x1C
#define REG_MIDL 0x1D
#define REG16_CHIDH 0x300A
#define REG16_CHIDL 0x300B
typedef enum {
OV9650_PID = 0x96,
OV7725_PID = 0x77,
OV2640_PID = 0x26,
OV3660_PID = 0x36,
OV5640_PID = 0x56,
OV7670_PID = 0x76,
NT99141_PID = 0x14
} camera_pid_t;
typedef enum {
CAMERA_OV7725,
CAMERA_OV2640,
CAMERA_OV3660,
CAMERA_OV5640,
CAMERA_OV7670,
CAMERA_NT99141,
CAMERA_MODEL_MAX,
CAMERA_NONE,
CAMERA_UNKNOWN
} camera_model_t;
typedef enum {
OV2640_SCCB_ADDR = 0x30,
OV5640_SCCB_ADDR = 0x3C,
OV3660_SCCB_ADDR = 0x3C,
OV7725_SCCB_ADDR = 0x21,
OV7670_SCCB_ADDR = 0x21,
NT99141_SCCB_ADDR = 0x2A,
} camera_sccb_addr_t;
typedef enum {
PIXFORMAT_RGB565, // 2BPP/RGB565
@ -58,6 +90,13 @@ typedef enum {
FRAMESIZE_INVALID
} framesize_t;
typedef struct {
const camera_model_t model;
const camera_sccb_addr_t sccb_addr;
const camera_pid_t pid;
const framesize_t max_size;
} camera_sensor_info_t;
typedef enum {
ASPECT_RATIO_4X3,
ASPECT_RATIO_3X2,
@ -101,6 +140,8 @@ typedef struct {
// Resolution table (in sensor.c)
extern const resolution_info_t resolution[];
// camera sensor table (in sensor.c)
extern const camera_sensor_info_t camera_sensor[];
typedef struct {
uint8_t MIDH;

@ -24,6 +24,10 @@
#if ESP_IDF_VERSION_MAJOR >= 4 // IDF 4+
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
#include "esp32/spiram.h"
#elif CONFIG_IDF_TARGET_ESP32S2
#include "esp32s2/spiram.h"
#elif CONFIG_IDF_TARGET_ESP32S3
#include "esp32s3/spiram.h"
#else
#error Target CONFIG_IDF_TARGET is not supported
#endif
@ -115,6 +119,54 @@ static bool _rgb_write(void * arg, uint16_t x, uint16_t y, uint16_t w, uint16_t
return true;
}
static bool _rgb565_write(void * arg, uint16_t x, uint16_t y, uint16_t w, uint16_t h, uint8_t *data)
{
rgb_jpg_decoder * jpeg = (rgb_jpg_decoder *)arg;
if(!data){
if(x == 0 && y == 0){
//write start
jpeg->width = w;
jpeg->height = h;
//if output is null, this is BMP
if(!jpeg->output){
jpeg->output = (uint8_t *)_malloc((w*h*3)+jpeg->data_offset);
if(!jpeg->output){
return false;
}
}
} else {
//write end
}
return true;
}
size_t jw = jpeg->width*3;
size_t jw2 = jpeg->width*2;
size_t t = y * jw;
size_t t2 = y * jw2;
size_t b = t + (h * jw);
size_t l = x * 2;
uint8_t *out = jpeg->output+jpeg->data_offset;
uint8_t *o = out;
size_t iy, iy2, ix, ix2;
w = w * 3;
for(iy=t, iy2=t2; iy<b; iy+=jw, iy2+=jw2) {
o = out+iy2+l;
for(ix2=ix=0; ix<w; ix+= 3, ix2 +=2) {
uint16_t r = data[ix];
uint16_t g = data[ix+1];
uint16_t b = data[ix+2];
uint16_t c = ((r & 0xF8) << 8) | ((g & 0xFC) << 3) | (b >> 3);
o[ix2+1] = c>>8;
o[ix2] = c&0xff;
}
data+=w;
}
return true;
}
//input buffer
static uint32_t _jpg_read(void * arg, size_t index, uint8_t *buf, size_t len)
{
@ -140,6 +192,21 @@ static bool jpg2rgb888(const uint8_t *src, size_t src_len, uint8_t * out, jpg_sc
return true;
}
bool jpg2rgb565(const uint8_t *src, size_t src_len, uint8_t * out, jpg_scale_t scale)
{
rgb_jpg_decoder jpeg;
jpeg.width = 0;
jpeg.height = 0;
jpeg.input = src;
jpeg.output = out;
jpeg.data_offset = 0;
if(esp_jpg_decode(src_len, scale, _jpg_read, _rgb565_write, (void*)&jpeg) != ESP_OK){
return false;
}
return true;
}
bool jpg2bmp(const uint8_t *src, size_t src_len, uint8_t ** out, size_t * out_len)
{

@ -25,6 +25,10 @@
#if ESP_IDF_VERSION_MAJOR >= 4 // IDF 4+
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
#include "esp32/spiram.h"
#elif CONFIG_IDF_TARGET_ESP32S2
#include "esp32s2/spiram.h"
#elif CONFIG_IDF_TARGET_ESP32S3
#include "esp32s3/spiram.h"
#else
#error Target CONFIG_IDF_TARGET is not supported
#endif
@ -195,7 +199,7 @@ public:
return true;
}
if ((size_t)len > (max_len - index)) {
ESP_LOGW(TAG, "JPG output overflow: %d bytes", len - (max_len - index));
//ESP_LOGW(TAG, "JPG output overflow: %d bytes (%d,%d,%d)", len - (max_len - index), len, index, max_len);
len = max_len - index;
}
if (len) {
@ -215,7 +219,7 @@ bool fmt2jpg(uint8_t *src, size_t src_len, uint16_t width, uint16_t height, pixf
{
//todo: allocate proper buffer for holding JPEG data
//this should be enough for CIF frame size
int jpg_buf_len = 64*1024;
int jpg_buf_len = 128*1024;
uint8_t * jpg_buf = (uint8_t *)_malloc(jpg_buf_len);

@ -1,432 +0,0 @@
/*
si2c.c - Software I2C library for ESP31B
Copyright (c) 2015 Hristo Gochkov. All rights reserved.
This file is part of the ESP31B core for Arduino environment.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include <stdint.h>
#include <stdbool.h>
#include "twi.h"
#include "soc/gpio_reg.h"
#include "soc/gpio_struct.h"
#include "soc/io_mux_reg.h"
#include "driver/rtc_io.h"
#include <stdio.h>
#define LOW 0x0
#define HIGH 0x1
//GPIO FUNCTIONS
#define INPUT 0x01
#define OUTPUT 0x02
#define PULLUP 0x04
#define INPUT_PULLUP 0x05
#define PULLDOWN 0x08
#define INPUT_PULLDOWN 0x09
#define OPEN_DRAIN 0x10
#define OUTPUT_OPEN_DRAIN 0x12
#define SPECIAL 0xF0
#define FUNCTION_1 0x00
#define FUNCTION_2 0x20
#define FUNCTION_3 0x40
#define FUNCTION_4 0x60
#define FUNCTION_5 0x80
#define FUNCTION_6 0xA0
#define ESP_REG(addr) *((volatile uint32_t *)(addr))
const uint8_t pin_to_mux[40] = { 0x44, 0x88, 0x40, 0x84, 0x48, 0x6c, 0x60, 0x64, 0x68, 0x54, 0x58, 0x5c, 0x34, 0x38, 0x30, 0x3c, 0x4c, 0x50, 0x70, 0x74, 0x78, 0x7c, 0x80, 0x8c, 0, 0x24, 0x28, 0x2c, 0, 0, 0, 0, 0x1c, 0x20, 0x14, 0x18, 0x04, 0x08, 0x0c, 0x10};
static void pinMode(uint8_t pin, uint8_t mode)
{
if(pin >= 40) {
return;
}
uint32_t rtc_reg = rtc_gpio_desc[pin].reg;
//RTC pins PULL settings
if(rtc_reg) {
//lock rtc
ESP_REG(rtc_reg) = ESP_REG(rtc_reg) & ~(rtc_gpio_desc[pin].mux);
if(mode & PULLUP) {
ESP_REG(rtc_reg) = (ESP_REG(rtc_reg) | rtc_gpio_desc[pin].pullup) & ~(rtc_gpio_desc[pin].pulldown);
} else if(mode & PULLDOWN) {
ESP_REG(rtc_reg) = (ESP_REG(rtc_reg) | rtc_gpio_desc[pin].pulldown) & ~(rtc_gpio_desc[pin].pullup);
} else {
ESP_REG(rtc_reg) = ESP_REG(rtc_reg) & ~(rtc_gpio_desc[pin].pullup | rtc_gpio_desc[pin].pulldown);
}
//unlock rtc
}
uint32_t pinFunction = 0, pinControl = 0;
//lock gpio
if(mode & INPUT) {
if(pin < 32) {
GPIO.enable_w1tc = BIT(pin);
} else {
GPIO.enable1_w1tc.val = BIT(pin - 32);
}
} else if(mode & OUTPUT) {
if(pin > 33) {
//unlock gpio
return;//pins above 33 can be only inputs
} else if(pin < 32) {
GPIO.enable_w1ts = BIT(pin);
} else {
GPIO.enable1_w1ts.val = BIT(pin - 32);
}
}
if(mode & PULLUP) {
pinFunction |= FUN_PU;
} else if(mode & PULLDOWN) {
pinFunction |= FUN_PD;
}
pinFunction |= ((uint32_t)2 << FUN_DRV_S);//what are the drivers?
pinFunction |= FUN_IE;//input enable but required for output as well?
if(mode & (INPUT | OUTPUT)) {
pinFunction |= ((uint32_t)2 << MCU_SEL_S);
} else if(mode == SPECIAL) {
pinFunction |= ((uint32_t)(((pin)==1||(pin)==3)?0:1) << MCU_SEL_S);
} else {
pinFunction |= ((uint32_t)(mode >> 5) << MCU_SEL_S);
}
ESP_REG(DR_REG_IO_MUX_BASE + pin_to_mux[pin]) = pinFunction;
if(mode & OPEN_DRAIN) {
pinControl = (1 << GPIO_PIN0_PAD_DRIVER_S);
}
GPIO.pin[pin].val = pinControl;
//unlock gpio
}
static void digitalWrite(uint8_t pin, uint8_t val)
{
if(val) {
if(pin < 32) {
GPIO.out_w1ts = BIT(pin);
} else if(pin < 34) {
GPIO.out1_w1ts.val = BIT(pin - 32);
}
} else {
if(pin < 32) {
GPIO.out_w1tc = BIT(pin);
} else if(pin < 34) {
GPIO.out1_w1tc.val = BIT(pin - 32);
}
}
}
unsigned char twi_dcount = 18;
static unsigned char twi_sda, twi_scl;
static inline void SDA_LOW()
{
//Enable SDA (becomes output and since GPO is 0 for the pin,
// it will pull the line low)
if (twi_sda < 32) {
GPIO.enable_w1ts = BIT(twi_sda);
} else {
GPIO.enable1_w1ts.val = BIT(twi_sda - 32);
}
}
static inline void SDA_HIGH()
{
//Disable SDA (becomes input and since it has pullup it will go high)
if (twi_sda < 32) {
GPIO.enable_w1tc = BIT(twi_sda);
} else {
GPIO.enable1_w1tc.val = BIT(twi_sda - 32);
}
}
static inline uint32_t SDA_READ()
{
if (twi_sda < 32) {
return (GPIO.in & BIT(twi_sda)) != 0;
} else {
return (GPIO.in1.val & BIT(twi_sda - 32)) != 0;
}
}
static void SCL_LOW()
{
if (twi_scl < 32) {
GPIO.enable_w1ts = BIT(twi_scl);
} else {
GPIO.enable1_w1ts.val = BIT(twi_scl - 32);
}
}
static void SCL_HIGH()
{
if (twi_scl < 32) {
GPIO.enable_w1tc = BIT(twi_scl);
} else {
GPIO.enable1_w1tc.val = BIT(twi_scl - 32);
}
}
static uint32_t SCL_READ()
{
if (twi_scl < 32) {
return (GPIO.in & BIT(twi_scl)) != 0;
} else {
return (GPIO.in1.val & BIT(twi_scl - 32)) != 0;
}
}
#ifndef FCPU80
#define FCPU80 80000000L
#endif
#if F_CPU == FCPU80
#define TWI_CLOCK_STRETCH 800
#else
#define TWI_CLOCK_STRETCH 1600
#endif
void twi_setClock(unsigned int freq)
{
#if F_CPU == FCPU80
if(freq <= 100000) {
twi_dcount = 19; //about 100KHz
} else if(freq <= 200000) {
twi_dcount = 8; //about 200KHz
} else if(freq <= 300000) {
twi_dcount = 3; //about 300KHz
} else if(freq <= 400000) {
twi_dcount = 1; //about 400KHz
} else {
twi_dcount = 1; //about 400KHz
}
#else
if(freq <= 100000) {
twi_dcount = 32; //about 100KHz
} else if(freq <= 200000) {
twi_dcount = 14; //about 200KHz
} else if(freq <= 300000) {
twi_dcount = 8; //about 300KHz
} else if(freq <= 400000) {
twi_dcount = 5; //about 400KHz
} else if(freq <= 500000) {
twi_dcount = 3; //about 500KHz
} else if(freq <= 600000) {
twi_dcount = 2; //about 600KHz
} else {
twi_dcount = 1; //about 700KHz
}
#endif
}
void twi_init(unsigned char sda, unsigned char scl)
{
twi_sda = sda;
twi_scl = scl;
pinMode(twi_sda, OUTPUT);
pinMode(twi_scl, OUTPUT);
digitalWrite(twi_sda, 0);
digitalWrite(twi_scl, 0);
pinMode(twi_sda, INPUT_PULLUP);
pinMode(twi_scl, INPUT_PULLUP);
twi_setClock(100000);
}
void twi_stop(void)
{
pinMode(twi_sda, INPUT);
pinMode(twi_scl, INPUT);
}
static void twi_delay(unsigned char v)
{
unsigned int i;
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-but-set-variable"
unsigned int reg;
for(i=0; i<v; i++) {
reg = REG_READ(GPIO_IN_REG);
}
#pragma GCC diagnostic pop
}
static bool twi_write_start(void)
{
SCL_HIGH();
SDA_HIGH();
if (SDA_READ() == 0) {
return false;
}
twi_delay(twi_dcount);
SDA_LOW();
twi_delay(twi_dcount);
return true;
}
static bool twi_write_stop(void)
{
unsigned int i = 0;
SCL_LOW();
SDA_LOW();
twi_delay(twi_dcount);
SCL_HIGH();
while (SCL_READ() == 0 && (i++) < TWI_CLOCK_STRETCH);// Clock stretching (up to 100us)
twi_delay(twi_dcount);
SDA_HIGH();
twi_delay(twi_dcount);
return true;
}
bool do_log = false;
static bool twi_write_bit(bool bit)
{
unsigned int i = 0;
SCL_LOW();
if (bit) {
SDA_HIGH();
if (do_log) {
twi_delay(twi_dcount+1);
}
} else {
SDA_LOW();
if (do_log) {}
}
twi_delay(twi_dcount+1);
SCL_HIGH();
while (SCL_READ() == 0 && (i++) < TWI_CLOCK_STRETCH);// Clock stretching (up to 100us)
twi_delay(twi_dcount);
return true;
}
static bool twi_read_bit(void)
{
unsigned int i = 0;
SCL_LOW();
SDA_HIGH();
twi_delay(twi_dcount+2);
SCL_HIGH();
while (SCL_READ() == 0 && (i++) < TWI_CLOCK_STRETCH);// Clock stretching (up to 100us)
bool bit = SDA_READ();
twi_delay(twi_dcount);
return bit;
}
static bool twi_write_byte(unsigned char byte)
{
if (byte == 0x43) {
// printf("TWB %02x ", (uint32_t) byte);
// do_log = true;
}
unsigned char bit;
for (bit = 0; bit < 8; bit++) {
twi_write_bit((byte & 0x80) != 0);
byte <<= 1;
}
if (do_log) {
printf("\n");
do_log = false;
}
return !twi_read_bit();//NACK/ACK
}
static unsigned char twi_read_byte(bool nack)
{
unsigned char byte = 0;
unsigned char bit;
for (bit = 0; bit < 8; bit++) {
byte = (byte << 1) | twi_read_bit();
}
twi_write_bit(nack);
return byte;
}
unsigned char twi_writeTo(unsigned char address, unsigned char * buf, unsigned int len, unsigned char sendStop)
{
unsigned int i;
if(!twi_write_start()) {
return 4; //line busy
}
if(!twi_write_byte(((address << 1) | 0) & 0xFF)) {
if (sendStop) {
twi_write_stop();
}
return 2; //received NACK on transmit of address
}
for(i=0; i<len; i++) {
if(!twi_write_byte(buf[i])) {
if (sendStop) {
twi_write_stop();
}
return 3;//received NACK on transmit of data
}
}
if(sendStop) {
twi_write_stop();
}
i = 0;
while(SDA_READ() == 0 && (i++) < 10) {
SCL_LOW();
twi_delay(twi_dcount);
SCL_HIGH();
twi_delay(twi_dcount);
}
return 0;
}
unsigned char twi_readFrom(unsigned char address, unsigned char* buf, unsigned int len, unsigned char sendStop)
{
unsigned int i;
if(!twi_write_start()) {
return 4; //line busy
}
if(!twi_write_byte(((address << 1) | 1) & 0xFF)) {
if (sendStop) {
twi_write_stop();
}
return 2;//received NACK on transmit of address
}
for(i=0; i<(len-1); i++) {
buf[i] = twi_read_byte(false);
}
buf[len-1] = twi_read_byte(true);
if(sendStop) {
twi_write_stop();
}
i = 0;
while(SDA_READ() == 0 && (i++) < 10) {
SCL_LOW();
twi_delay(twi_dcount);
SCL_HIGH();
twi_delay(twi_dcount);
}
return 0;
}

@ -1,38 +0,0 @@
/*
twi.h - Software I2C library for ESP31B
Copyright (c) 2015 Hristo Gochkov. All rights reserved.
This file is part of the ESP31B core for Arduino environment.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifndef SI2C_h
#define SI2C_h
#ifdef __cplusplus
extern "C" {
#endif
void twi_init(unsigned char sda, unsigned char scl);
void twi_stop(void);
void twi_setClock(unsigned int freq);
uint8_t twi_writeTo(unsigned char address, unsigned char * buf, unsigned int len, unsigned char sendStop);
uint8_t twi_readFrom(unsigned char address, unsigned char * buf, unsigned int len, unsigned char sendStop);
#ifdef __cplusplus
}
#endif
#endif

@ -15,9 +15,13 @@ static const char* TAG = "camera_xclk";
esp_err_t xclk_timer_conf(int ledc_timer, int xclk_freq_hz)
{
ledc_timer_config_t timer_conf;
timer_conf.duty_resolution = 2;
timer_conf.duty_resolution = LEDC_TIMER_1_BIT;
timer_conf.freq_hz = xclk_freq_hz;
#if CONFIG_IDF_TARGET_ESP32
timer_conf.speed_mode = LEDC_HIGH_SPEED_MODE;
#else
timer_conf.speed_mode = LEDC_LOW_SPEED_MODE;
#endif
#if ESP_IDF_VERSION_MAJOR >= 4
timer_conf.clk_cfg = LEDC_AUTO_CLK;
#endif
@ -41,11 +45,15 @@ esp_err_t camera_enable_out_clock(camera_config_t* config)
ledc_channel_config_t ch_conf;
ch_conf.gpio_num = config->pin_xclk;
#if CONFIG_IDF_TARGET_ESP32
ch_conf.speed_mode = LEDC_HIGH_SPEED_MODE;
#else
ch_conf.speed_mode = LEDC_LOW_SPEED_MODE;
#endif
ch_conf.channel = config->ledc_channel;
ch_conf.intr_type = LEDC_INTR_DISABLE;
ch_conf.timer_sel = config->ledc_timer;
ch_conf.duty = 2;
ch_conf.duty = 1;
ch_conf.hpoint = 0;
err = ledc_channel_config(&ch_conf);
if (err != ESP_OK) {

Loading…
Cancel
Save