diff --git a/include/camera_pins.h b/include/camera_pins.h new file mode 100644 index 0000000..18ceb76 --- /dev/null +++ b/include/camera_pins.h @@ -0,0 +1,297 @@ +#if defined(CAMERA_MODEL_WROVER_KIT) +#define PWDN_GPIO_NUM -1 +#define RESET_GPIO_NUM -1 +#define XCLK_GPIO_NUM 21 +#define SIOD_GPIO_NUM 26 +#define SIOC_GPIO_NUM 27 + +#define Y9_GPIO_NUM 35 +#define Y8_GPIO_NUM 34 +#define Y7_GPIO_NUM 39 +#define Y6_GPIO_NUM 36 +#define Y5_GPIO_NUM 19 +#define Y4_GPIO_NUM 18 +#define Y3_GPIO_NUM 5 +#define Y2_GPIO_NUM 4 +#define VSYNC_GPIO_NUM 25 +#define HREF_GPIO_NUM 23 +#define PCLK_GPIO_NUM 22 + +#elif defined(CAMERA_MODEL_ESP_EYE) +#define PWDN_GPIO_NUM -1 +#define RESET_GPIO_NUM -1 +#define XCLK_GPIO_NUM 4 +#define SIOD_GPIO_NUM 18 +#define SIOC_GPIO_NUM 23 + +#define Y9_GPIO_NUM 36 +#define Y8_GPIO_NUM 37 +#define Y7_GPIO_NUM 38 +#define Y6_GPIO_NUM 39 +#define Y5_GPIO_NUM 35 +#define Y4_GPIO_NUM 14 +#define Y3_GPIO_NUM 13 +#define Y2_GPIO_NUM 34 +#define VSYNC_GPIO_NUM 5 +#define HREF_GPIO_NUM 27 +#define PCLK_GPIO_NUM 25 + +#define LED_GPIO_NUM 22 + +#elif defined(CAMERA_MODEL_M5STACK_PSRAM) +#define PWDN_GPIO_NUM -1 +#define RESET_GPIO_NUM 15 +#define XCLK_GPIO_NUM 27 +#define SIOD_GPIO_NUM 25 +#define SIOC_GPIO_NUM 23 + +#define Y9_GPIO_NUM 19 +#define Y8_GPIO_NUM 36 +#define Y7_GPIO_NUM 18 +#define Y6_GPIO_NUM 39 +#define Y5_GPIO_NUM 5 +#define Y4_GPIO_NUM 34 +#define Y3_GPIO_NUM 35 +#define Y2_GPIO_NUM 32 +#define VSYNC_GPIO_NUM 22 +#define HREF_GPIO_NUM 26 +#define PCLK_GPIO_NUM 21 + +#elif defined(CAMERA_MODEL_M5STACK_V2_PSRAM) +#define PWDN_GPIO_NUM -1 +#define RESET_GPIO_NUM 15 +#define XCLK_GPIO_NUM 27 +#define SIOD_GPIO_NUM 22 +#define SIOC_GPIO_NUM 23 + +#define Y9_GPIO_NUM 19 +#define Y8_GPIO_NUM 36 +#define Y7_GPIO_NUM 18 +#define Y6_GPIO_NUM 39 +#define Y5_GPIO_NUM 5 +#define Y4_GPIO_NUM 34 +#define Y3_GPIO_NUM 35 +#define Y2_GPIO_NUM 32 +#define VSYNC_GPIO_NUM 25 +#define HREF_GPIO_NUM 26 +#define PCLK_GPIO_NUM 21 + +#elif defined(CAMERA_MODEL_M5STACK_WIDE) +#define PWDN_GPIO_NUM -1 +#define RESET_GPIO_NUM 15 +#define XCLK_GPIO_NUM 27 +#define SIOD_GPIO_NUM 22 +#define SIOC_GPIO_NUM 23 + +#define Y9_GPIO_NUM 19 +#define Y8_GPIO_NUM 36 +#define Y7_GPIO_NUM 18 +#define Y6_GPIO_NUM 39 +#define Y5_GPIO_NUM 5 +#define Y4_GPIO_NUM 34 +#define Y3_GPIO_NUM 35 +#define Y2_GPIO_NUM 32 +#define VSYNC_GPIO_NUM 25 +#define HREF_GPIO_NUM 26 +#define PCLK_GPIO_NUM 21 + +#define LED_GPIO_NUM 2 + +#elif defined(CAMERA_MODEL_M5STACK_ESP32CAM) +#define PWDN_GPIO_NUM -1 +#define RESET_GPIO_NUM 15 +#define XCLK_GPIO_NUM 27 +#define SIOD_GPIO_NUM 25 +#define SIOC_GPIO_NUM 23 + +#define Y9_GPIO_NUM 19 +#define Y8_GPIO_NUM 36 +#define Y7_GPIO_NUM 18 +#define Y6_GPIO_NUM 39 +#define Y5_GPIO_NUM 5 +#define Y4_GPIO_NUM 34 +#define Y3_GPIO_NUM 35 +#define Y2_GPIO_NUM 17 +#define VSYNC_GPIO_NUM 22 +#define HREF_GPIO_NUM 26 +#define PCLK_GPIO_NUM 21 + +#elif defined(CAMERA_MODEL_M5STACK_UNITCAM) +#define PWDN_GPIO_NUM -1 +#define RESET_GPIO_NUM 15 +#define XCLK_GPIO_NUM 27 +#define SIOD_GPIO_NUM 25 +#define SIOC_GPIO_NUM 23 + +#define Y9_GPIO_NUM 19 +#define Y8_GPIO_NUM 36 +#define Y7_GPIO_NUM 18 +#define Y6_GPIO_NUM 39 +#define Y5_GPIO_NUM 5 +#define Y4_GPIO_NUM 34 +#define Y3_GPIO_NUM 35 +#define Y2_GPIO_NUM 32 +#define VSYNC_GPIO_NUM 22 +#define HREF_GPIO_NUM 26 +#define PCLK_GPIO_NUM 21 + +#elif defined(CAMERA_MODEL_AI_THINKER) +#define PWDN_GPIO_NUM 32 +#define RESET_GPIO_NUM -1 +#define XCLK_GPIO_NUM 0 +#define SIOD_GPIO_NUM 26 +#define SIOC_GPIO_NUM 27 + +#define Y9_GPIO_NUM 35 +#define Y8_GPIO_NUM 34 +#define Y7_GPIO_NUM 39 +#define Y6_GPIO_NUM 36 +#define Y5_GPIO_NUM 21 +#define Y4_GPIO_NUM 19 +#define Y3_GPIO_NUM 18 +#define Y2_GPIO_NUM 5 +#define VSYNC_GPIO_NUM 25 +#define HREF_GPIO_NUM 23 +#define PCLK_GPIO_NUM 22 + +// 4 for flash led or 33 for normal led +#define LED_GPIO_NUM 4 + +#elif defined(CAMERA_MODEL_TTGO_T_JOURNAL) +#define PWDN_GPIO_NUM 0 +#define RESET_GPIO_NUM 15 +#define XCLK_GPIO_NUM 27 +#define SIOD_GPIO_NUM 25 +#define SIOC_GPIO_NUM 23 + +#define Y9_GPIO_NUM 19 +#define Y8_GPIO_NUM 36 +#define Y7_GPIO_NUM 18 +#define Y6_GPIO_NUM 39 +#define Y5_GPIO_NUM 5 +#define Y4_GPIO_NUM 34 +#define Y3_GPIO_NUM 35 +#define Y2_GPIO_NUM 17 +#define VSYNC_GPIO_NUM 22 +#define HREF_GPIO_NUM 26 +#define PCLK_GPIO_NUM 21 + +#elif defined(CAMERA_MODEL_XIAO_ESP32S3) +#define PWDN_GPIO_NUM -1 +#define RESET_GPIO_NUM -1 +#define XCLK_GPIO_NUM 10 +#define SIOD_GPIO_NUM 40 +#define SIOC_GPIO_NUM 39 + +#define Y9_GPIO_NUM 48 +#define Y8_GPIO_NUM 11 +#define Y7_GPIO_NUM 12 +#define Y6_GPIO_NUM 14 +#define Y5_GPIO_NUM 16 +#define Y4_GPIO_NUM 18 +#define Y3_GPIO_NUM 17 +#define Y2_GPIO_NUM 15 +#define VSYNC_GPIO_NUM 38 +#define HREF_GPIO_NUM 47 +#define PCLK_GPIO_NUM 13 + +#elif defined(CAMERA_MODEL_ESP32_CAM_BOARD) +// The 18 pin header on the board has Y5 and Y3 swapped +#define USE_BOARD_HEADER 0 +#define PWDN_GPIO_NUM 32 +#define RESET_GPIO_NUM 33 +#define XCLK_GPIO_NUM 4 +#define SIOD_GPIO_NUM 18 +#define SIOC_GPIO_NUM 23 + +#define Y9_GPIO_NUM 36 +#define Y8_GPIO_NUM 19 +#define Y7_GPIO_NUM 21 +#define Y6_GPIO_NUM 39 +#if USE_BOARD_HEADER +#define Y5_GPIO_NUM 13 +#else +#define Y5_GPIO_NUM 35 +#endif +#define Y4_GPIO_NUM 14 +#if USE_BOARD_HEADER +#define Y3_GPIO_NUM 35 +#else +#define Y3_GPIO_NUM 13 +#endif +#define Y2_GPIO_NUM 34 +#define VSYNC_GPIO_NUM 5 +#define HREF_GPIO_NUM 27 +#define PCLK_GPIO_NUM 25 + +#elif defined(CAMERA_MODEL_ESP32S3_CAM_LCD) +#define PWDN_GPIO_NUM -1 +#define RESET_GPIO_NUM -1 +#define XCLK_GPIO_NUM 40 +#define SIOD_GPIO_NUM 17 +#define SIOC_GPIO_NUM 18 + +#define Y9_GPIO_NUM 39 +#define Y8_GPIO_NUM 41 +#define Y7_GPIO_NUM 42 +#define Y6_GPIO_NUM 12 +#define Y5_GPIO_NUM 3 +#define Y4_GPIO_NUM 14 +#define Y3_GPIO_NUM 47 +#define Y2_GPIO_NUM 13 +#define VSYNC_GPIO_NUM 21 +#define HREF_GPIO_NUM 38 +#define PCLK_GPIO_NUM 11 + +#elif defined(CAMERA_MODEL_ESP32S2_CAM_BOARD) +// The 18 pin header on the board has Y5 and Y3 swapped +#define USE_BOARD_HEADER 0 +#define PWDN_GPIO_NUM 1 +#define RESET_GPIO_NUM 2 +#define XCLK_GPIO_NUM 42 +#define SIOD_GPIO_NUM 41 +#define SIOC_GPIO_NUM 18 + +#define Y9_GPIO_NUM 16 +#define Y8_GPIO_NUM 39 +#define Y7_GPIO_NUM 40 +#define Y6_GPIO_NUM 15 +#if USE_BOARD_HEADER +#define Y5_GPIO_NUM 12 +#else +#define Y5_GPIO_NUM 13 +#endif +#define Y4_GPIO_NUM 5 +#if USE_BOARD_HEADER +#define Y3_GPIO_NUM 13 +#else +#define Y3_GPIO_NUM 12 +#endif +#define Y2_GPIO_NUM 14 +#define VSYNC_GPIO_NUM 38 +#define HREF_GPIO_NUM 4 +#define PCLK_GPIO_NUM 3 + +#elif defined(CAMERA_MODEL_ESP32S3_EYE) +#define PWDN_GPIO_NUM -1 +#define RESET_GPIO_NUM -1 +#define XCLK_GPIO_NUM 15 +#define SIOD_GPIO_NUM 4 +#define SIOC_GPIO_NUM 5 + +#define Y2_GPIO_NUM 11 +#define Y3_GPIO_NUM 9 +#define Y4_GPIO_NUM 8 +#define Y5_GPIO_NUM 10 +#define Y6_GPIO_NUM 12 +#define Y7_GPIO_NUM 18 +#define Y8_GPIO_NUM 17 +#define Y9_GPIO_NUM 16 + +#define VSYNC_GPIO_NUM 6 +#define HREF_GPIO_NUM 7 +#define PCLK_GPIO_NUM 13 + +#else +#error "Camera model not selected" +#endif \ No newline at end of file diff --git a/platformio.ini b/platformio.ini index e58fde5..9c9f08b 100644 --- a/platformio.ini +++ b/platformio.ini @@ -13,3 +13,10 @@ platform = espressif32 board = esp32cam monitor_speed = 115200 framework = arduino +lib_deps = + ;ottowinter/ESPAsyncWebServer-esphome@^2.1.0 + teckel12/NewPing@^1.9.7 + rfetick/MPU6050_light@^1.1.0 + adafruit/Adafruit PWM Servo Driver Library@^2.4.1 + adafruit/Adafruit SSD1306@^2.5.7 + adafruit/Adafruit GFX Library@^1.11.5 \ No newline at end of file diff --git a/src/main.cpp b/src/main.cpp new file mode 100644 index 0000000..fdf14ba --- /dev/null +++ b/src/main.cpp @@ -0,0 +1,288 @@ +#include "esp_camera.h" +#include +#include "esp_timer.h" +#include "img_converters.h" +#include "Arduino.h" +#include "fb_gfx.h" +#include "soc/soc.h" +#include "soc/rtc_cntl_reg.h" +#include "esp_http_server.h" + +#include +#include +#include "Wire.h" +#include +#include +#include +#include + +#define CAMERA_MODEL_AI_THINKER +#include + +const char* ssid = "SSID"; +const char* password = "PASSWORD"; + +#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"; + +#define SCREEN_WIDTH 128 +#define SCREEN_HEIGHT 64 + +int buttonLed = 2; +int button = 16; + +NewPing sonar[2] = { + NewPing(12, 12, 200), + NewPing(13, 13, 200) +}; + +MPU6050 mpu(Wire); +Adafruit_PWMServoDriver pwm = Adafruit_PWMServoDriver(0x40); +Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, -1); + +httpd_handle_t stream_httpd = NULL; + +long timer = 0; +static unsigned long last_interrupt_time = 0; +bool servosEnabled = true; + +void toggleServo(){ + Serial.print("Servos is enabled:"); + Serial.println(servosEnabled); + //if(servosEnabled){ + // pwm.sleep(); + //} else { + // pwm.wakeup(); + //} + servosEnabled = !servosEnabled; +} + +void IRAM_ATTR powerToggle(){ + unsigned long interrupt_time = millis(); + if (interrupt_time - last_interrupt_time > 200) { + toggleServo(); + digitalWrite(buttonLed, servosEnabled); + } + last_interrupt_time = interrupt_time; +} + +static esp_err_t stream_handler(httpd_req_t *req){ + camera_fb_t * fb = NULL; + esp_err_t res = ESP_OK; + size_t _jpg_buf_len = 0; + uint8_t * _jpg_buf = NULL; + char * part_buf[64]; + + res = httpd_resp_set_type(req, _STREAM_CONTENT_TYPE); + if(res != ESP_OK){ + return res; + } + + while(true){ + fb = esp_camera_fb_get(); + if (!fb) { + Serial.println("Camera capture failed"); + res = ESP_FAIL; + } else { + if(fb->width > 400){ + if(fb->format != PIXFORMAT_JPEG){ + bool jpeg_converted = frame2jpg(fb, 80, &_jpg_buf, &_jpg_buf_len); + esp_camera_fb_return(fb); + fb = NULL; + if(!jpeg_converted){ + Serial.println("JPEG compression failed"); + res = ESP_FAIL; + } + } else { + _jpg_buf_len = fb->len; + _jpg_buf = fb->buf; + } + } + } + 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(res == ESP_OK){ + res = httpd_resp_send_chunk(req, _STREAM_BOUNDARY, strlen(_STREAM_BOUNDARY)); + } + if(fb){ + esp_camera_fb_return(fb); + fb = NULL; + _jpg_buf = NULL; + } else if(_jpg_buf){ + free(_jpg_buf); + _jpg_buf = NULL; + } + if(res != ESP_OK){ + break; + } + Serial.printf("MJPG: %uB\n",(uint32_t)(_jpg_buf_len)); + } + return res; +} + +void startCameraServer(){ + httpd_config_t config = HTTPD_DEFAULT_CONFIG(); + config.server_port = 80; + + httpd_uri_t index_uri = { + .uri = "/", + .method = HTTP_GET, + .handler = stream_handler, + .user_ctx = NULL + }; + + Serial.printf("Starting web server on port: '%d'\n", config.server_port); + if (httpd_start(&stream_httpd, &config) == ESP_OK) { + httpd_register_uri_handler(stream_httpd, &index_uri); + } +} + +void setupMPU(){ + Wire.begin(14, 15); + + byte status = mpu.begin(); + Serial.print(F("MPU6050 status: ")); + Serial.println(status); + while(status!=0){ + status = mpu.begin(); + Serial.print(F("MPU6050 status: ")); + Serial.println(status); + delay(500); + } // stop everything if could not connect to MPU6050 + + Serial.println(F("Calculating offsets, do not move MPU6050")); + delay(1000); + mpu.calcOffsets(true,true); // gyro and accelero + Serial.println("Done!\n"); +} + +void setupOLED(){ + if(!display.begin(SSD1306_SWITCHCAPVCC, 0x3C)) { + Serial.println(F("SSD1306 allocation failed")); + for(;;); // Don't proceed, loop forever + } + + display.display(); + delay(200); + display.clearDisplay(); +} + +void setupPWMController(){ + pwm.begin(); + pwm.setOscillatorFrequency(27000000); + pwm.setPWMFreq(50); +} + +void setup() { + WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0); + + Serial.begin(115200); + Serial.setDebugOutput(false); + + pinMode(buttonLed, OUTPUT); + pinMode(button, INPUT); + + attachInterrupt(button, powerToggle, RISING); + + setupMPU(); + setupOLED(); + setupPWMController(); + + camera_config_t config; + config.ledc_channel = LEDC_CHANNEL_0; + config.ledc_timer = LEDC_TIMER_0; + config.pin_d0 = Y2_GPIO_NUM; + config.pin_d1 = Y3_GPIO_NUM; + config.pin_d2 = Y4_GPIO_NUM; + config.pin_d3 = Y5_GPIO_NUM; + config.pin_d4 = Y6_GPIO_NUM; + config.pin_d5 = Y7_GPIO_NUM; + config.pin_d6 = Y8_GPIO_NUM; + config.pin_d7 = Y9_GPIO_NUM; + config.pin_xclk = XCLK_GPIO_NUM; + config.pin_pclk = PCLK_GPIO_NUM; + config.pin_vsync = VSYNC_GPIO_NUM; + config.pin_href = HREF_GPIO_NUM; + config.pin_sscb_sda = SIOD_GPIO_NUM; + config.pin_sscb_scl = SIOC_GPIO_NUM; + config.pin_pwdn = PWDN_GPIO_NUM; + config.pin_reset = RESET_GPIO_NUM; + config.xclk_freq_hz = 20000000; + config.pixel_format = PIXFORMAT_JPEG; + + if(psramFound()){ + config.frame_size = FRAMESIZE_VGA; + config.jpeg_quality = 10; + config.fb_count = 2; + } else { + config.frame_size = FRAMESIZE_SVGA; + config.jpeg_quality = 12; + config.fb_count = 1; + } + + // Camera init + esp_err_t err = esp_camera_init(&config); + if (err != ESP_OK) { + Serial.printf("Camera init failed with error 0x%x", err); + return; + } + // Wi-Fi connection + WiFi.begin(ssid, password); + while (WiFi.status() != WL_CONNECTED) { + delay(500); + Serial.print("."); + } + Serial.println(""); + Serial.println("WiFi connected"); + + Serial.print("Camera Stream Ready! Go to: http://"); + Serial.print(WiFi.localIP()); + display.setTextSize(2); // Normal 1:1 pixel scale + display.setTextColor(WHITE); // Draw white text + display.setCursor(0,0); // Start at top-left corner + display.println(WiFi.localIP()); + display.display(); + + startCameraServer(); +} + +void loop() { + delay(1); + /*for (uint8_t i = 0; i < 2; i++) { // Loop through each sensor and display results. + delay(200); // Wait 50ms between pings (about 20 pings/sec). 29ms should be the shortest delay between pings. + Serial.print(i); + Serial.print("="); + Serial.print(sonar[i].ping_cm()); + Serial.print("cm "); + } + mpu.update(); + + if(millis() - timer > 1000){ // print data every second + Serial.print(F("TEMPERATURE: "));Serial.println(mpu.getTemp()); + Serial.print(F("ACCELERO X: "));Serial.print(mpu.getAccX()); + Serial.print("\tY: ");Serial.print(mpu.getAccY()); + Serial.print("\tZ: ");Serial.println(mpu.getAccZ()); + + Serial.print(F("GYRO X: "));Serial.print(mpu.getGyroX()); + Serial.print("\tY: ");Serial.print(mpu.getGyroY()); + Serial.print("\tZ: ");Serial.println(mpu.getGyroZ()); + + Serial.print(F("ACC ANGLE X: "));Serial.print(mpu.getAccAngleX()); + Serial.print("\tY: ");Serial.println(mpu.getAccAngleY()); + + Serial.print(F("ANGLE X: "));Serial.print(mpu.getAngleX()); + Serial.print("\tY: ");Serial.print(mpu.getAngleY()); + Serial.print("\tZ: ");Serial.println(mpu.getAngleZ()); + Serial.println(F("=====================================================\n")); + timer = millis(); + }*/ +} +