Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

esp32-camera #26

Open
wants to merge 17 commits into
base: foxy
Choose a base branch
from
3 changes: 3 additions & 0 deletions NOTICE
Original file line number Diff line number Diff line change
Expand Up @@ -28,3 +28,6 @@ eProsima
Robert Bosch GmbH
Ralph Lange <[email protected]>
Raphael Vogelgsang <[email protected]>

Dor Ben Harush
Dor Ben Harush <[email protected]>
14 changes: 14 additions & 0 deletions apps/take_picture/app-colcon.meta
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
{
"names": {
"rmw_microxrcedds": {
"cmake-args": [
"-DRMW_UXRCE_MAX_NODES=1",
"-DRMW_UXRCE_MAX_PUBLISHERS=1",
"-DRMW_UXRCE_MAX_SUBSCRIPTIONS=0",
"-DRMW_UXRCE_MAX_SERVICES=0",
"-DRMW_UXRCE_MAX_CLIENTS=0",
"-DRMW_UXRCE_MAX_HISTORY=1",
]
}
}
}
197 changes: 197 additions & 0 deletions apps/take_picture/app.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,197 @@
/**
* This example takes a picture every 5s.
Example src: https://github.com/espressif/esp32-camera.git

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@ralph-lange parts from this example come from the example here. Do we need to mention that in 3rd-party-licenses.txt?
The license there is also Apache 2.0

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, all details (version, copyright statement, original license text) have to be provided in the 3rd-party-licenses.txt file, please. Furthermore, a short summary (one list item with one or two sentences) should go into the License section in README.md.

*/

#define BOARD_WROVER_KIT
#define BOARD_ESP32CAM_AITHINKER

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is it possible to add an option in menuconfig where one board is selected?

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

According to espressif the only difference is in the sdkconfig.defaults file.
In this line : CONFIG_ESP32_SPIRAM_SUPPORT=y
the line can be added menually like I did or it can be added in the menuconfig (Enable PSRAM).
Src: https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-guides/build-system.html#selecting-idf-target
and https://github.com/espressif/esp32-camera

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sorry I should have been more precise.
What I mean is that there are two defines here #define BOARD_WROVER_KIT and #define BOARD_ESP32CAM_AITHINKER they define which camera pinout to use (see Lines 35-79 ) and should be mutually exclusive.
Therefore I suggest to add an option to menuconfig where one of the two can be selected, which would also make it easier to add a new camera pinout for example the ESP-EYE development board.

Copy link
Author

@DorBenHarush DorBenHarush Aug 12, 2020

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Check my last commit I added the option to choose camera pinout.



// ================================ CODE ======================================

#include <esp_event_loop.h>
#include <esp_log.h>
#include <esp_system.h>
#include <nvs_flash.h>
#include <sys/param.h>
#include <string.h>

#include <stdio.h>
#include <unistd.h>

#include <rcl/rcl.h>
#include <rcl/error_handling.h>
#include <std_msgs/msg/int32.h>

#include <rclc/rclc.h>
#include <rclc/executor.h>


#include "freertos/FreeRTOS.h"
#include "freertos/task.h"

#include "esp_camera.h"

// WROVER-KIT PIN Map
#ifdef BOARD_WROVER_KIT

#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

#endif

// ESP32Cam (AiThinker) PIN Map
#ifdef BOARD_ESP32CAM_AITHINKER

#define CAM_PIN_PWDN 32
#define CAM_PIN_RESET -1 //software reset will be performed
#define CAM_PIN_XCLK 0
#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 21
#define CAM_PIN_D2 19
#define CAM_PIN_D1 18
#define CAM_PIN_D0 5
#define CAM_PIN_VSYNC 25
#define CAM_PIN_HREF 23
#define CAM_PIN_PCLK 22

#endif

static const char *TAG = "example:take_picture";


#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){printf("Failed status on line %d: %d. Aborting.\n",__LINE__,(int)temp_rc);vTaskDelete(NULL);}}
#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){printf("Failed status on line %d: %d. Continuing.\n",__LINE__,(int)temp_rc);}}

rcl_publisher_t publisher;
std_msgs__msg__Int32 msg;
camera_fb_t *pic;

void timer_callback(rcl_timer_t * timer, int64_t last_call_time)
{
UNUSED(last_call_time);
if (timer != NULL) {
RCSOFTCHECK(rcl_publish(&publisher, &msg, NULL));
// use pic->buf to access the image
msg.data = pic->len;
}
}


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 20MHz or 10MHz for OV2640 double FPS (Experimental)
.xclk_freq_hz = 20000000,
.ledc_timer = LEDC_TIMER_0,
.ledc_channel = LEDC_CHANNEL_0,

.pixel_format = PIXFORMAT_JPEG, //YUV422,GRAYSCALE,RGB565,JPEG
.frame_size = FRAMESIZE_VGA, //QQVGA-UXGA 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
};

static esp_err_t init_camera()
{
//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;
}

void appMain(void * arg)
{
init_camera();
rcl_allocator_t allocator = rcl_get_default_allocator();
rclc_support_t support;

// create init_options
RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));

// create node
rcl_node_t node = rcl_get_zero_initialized_node();
RCCHECK(rclc_node_init_default(&node, "freertos_pictureSize_publisher", "", &support));

// create publisher
RCCHECK(rclc_publisher_init_default(
&publisher,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
"freertos_pictureSize_publisher"));

// create timer,
rcl_timer_t timer = rcl_get_zero_initialized_timer();
const unsigned int timer_timeout = 1000;
RCCHECK(rclc_timer_init_default(
&timer,
&support,
RCL_MS_TO_NS(timer_timeout),
timer_callback));

// create executor
rclc_executor_t executor = rclc_executor_get_zero_initialized_executor();
RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));

unsigned int rcl_wait_timeout = 1000; // in ms
RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout)));
RCCHECK(rclc_executor_add_timer(&executor, &timer));

msg.data = 0;

while(1){
rclc_executor_spin_some(&executor, 100);
usleep(100000);
//takes picture
pic = esp_camera_fb_get();
vTaskDelay(5000 / portTICK_RATE_MS);
}

// free resources
RCCHECK(rcl_publisher_fini(&publisher, &node))
RCCHECK(rcl_node_fini(&node))
vTaskDelete(NULL);
}
65 changes: 65 additions & 0 deletions microros_esp32_extensions/main/Kconfig.projbuild
Original file line number Diff line number Diff line change
Expand Up @@ -54,3 +54,68 @@ menu "WiFi Configuration"
endmenu

endmenu
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 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
1 change: 1 addition & 0 deletions microros_esp32_extensions/sdkconfig.defaults
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
CONFIG_ESP_MAIN_TASK_STACK_SIZE=3000
CONFIG_FREERTOS_UNICORE=y
CONFIG_ESP_TASK_WDT=n
CONFIG_ESP32_SPIRAM_SUPPORT=y