#include "esp_camera.h" #include #include #include #include #include #include struct MOTOR_PINS { int pinEn; int pinIN1; int pinIN2; }; std::vector motorPins = { {12, 13, 15}, // RIGHT_MOTOR Pins (EnA, IN1, IN2) {12, 14, 2} // LEFT_MOTOR Pins (EnB, IN3, IN4) }; #define LIGHT_PIN 4 #define UP 1 #define DOWN 2 #define LEFT 3 #define RIGHT 4 #define STOP 0 #define RIGHT_MOTOR 0 #define LEFT_MOTOR 1 #define FORWARD 1 #define BACKWARD -1 const int PWMFreq = 1000; /* 1 KHz */ const int PWMResolution = 8; const int PWMSpeedChannel = 2; const int PWMLightChannel = 3; // Camera related constants #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 const char* ssid = "MyWiFiCar"; const char* password = "12345678"; AsyncWebServer server(80); AsyncWebSocket wsCamera("/Camera"); AsyncWebSocket wsCarInput("/CarInput"); uint32_t cameraClientId = 0; const char* htmlHomePage PROGMEM = R"HTMLHOMEPAGE(
)HTMLHOMEPAGE"; void rotateMotor(int motorNumber, int motorDirection) { if (motorDirection == FORWARD) { digitalWrite(motorPins[motorNumber].pinIN1, HIGH); digitalWrite(motorPins[motorNumber].pinIN2, LOW); } else if (motorDirection == BACKWARD) { digitalWrite(motorPins[motorNumber].pinIN1, LOW); digitalWrite(motorPins[motorNumber].pinIN2, HIGH); } else { digitalWrite(motorPins[motorNumber].pinIN1, LOW); digitalWrite(motorPins[motorNumber].pinIN2, LOW); } } void moveCar(int inputValue) { Serial.printf("Got value as %d\n", inputValue); switch(inputValue) { case UP: rotateMotor(RIGHT_MOTOR, FORWARD); rotateMotor(LEFT_MOTOR, FORWARD); break; case DOWN: rotateMotor(RIGHT_MOTOR, BACKWARD); rotateMotor(LEFT_MOTOR, BACKWARD); break; } } void onCarInputWebSocketEvent(AsyncWebSocket *server, AsyncWebSocketClient *client, AwsEventType type, void *arg, uint8_t *data, size_t len) { switch (type) { case WS_EVT_CONNECT: Serial.printf("WebSocket client #%u connected from %s\n", client->id(), client->remoteIP().toString().c_str()); break; case WS_EVT_DISCONNECT: Serial.printf("WebSocket client #%u disconnected\n", client->id()); moveCar(0); ledcWrite(PWMLightChannel, 0); break; case WS_EVT_DATA: { AwsFrameInfo *info = (AwsFrameInfo *)arg; if (info->final && info->index == 0 && info->len == len && info->opcode == WS_TEXT) { std::string myData((char *)data, len); std::istringstream ss(myData); std::string key, value; std::getline(ss, key, ','); std::getline(ss, value, ','); Serial.printf("Key [%s] Value[%s]\n", key.c_str(), value.c_str()); int valueInt = atoi(value.c_str()); if (key == "MoveCar") { moveCar(valueInt); } else if (key == "Speed") { ledcWrite(PWMSpeedChannel, valueInt); } else if (key == "Light") { ledcWrite(PWMLightChannel, valueInt); } } break; } case WS_EVT_PONG: case WS_EVT_ERROR: default: break; } } void onCameraWebSocketEvent(AsyncWebSocket *server, AsyncWebSocketClient *client, AwsEventType type, void *arg, uint8_t *data, size_t len) { switch (type) { case WS_EVT_CONNECT: Serial.printf("WebSocket client #%u connected from %s\n", client->id(), client->remoteIP().toString().c_str()); cameraClientId = client->id(); break; case WS_EVT_DISCONNECT: Serial.printf("WebSocket client #%u disconnected\n", client->id()); cameraClientId = 0; break; case WS_EVT_DATA: case WS_EVT_PONG: case WS_EVT_ERROR: default: break; } } void setupCamera() { 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; config.frame_size = FRAMESIZE_VGA; config.jpeg_quality = 10; config.fb_count = 1; esp_err_t err = esp_camera_init(&config); if (err != ESP_OK) { Serial.printf("Camera init failed with error 0x%x", err); return; } if (psramFound()) { heap_caps_malloc_extmem_enable(20000); Serial.println("PSRAM initialized. malloc to take memory from psram above this size"); } } void sendCameraPicture() { if (cameraClientId == 0) return; camera_fb_t *fb = esp_camera_fb_get(); if (!fb) { Serial.println("Frame buffer could not be acquired"); return; } wsCamera.binary(cameraClientId, fb->buf, fb->len); esp_camera_fb_return(fb); } void setUpPinModes() { ledcSetup(PWMSpeedChannel, PWMFreq, PWMResolution); ledcSetup(PWMLightChannel, PWMFreq, PWMResolution); for (const auto &motor : motorPins) { pinMode(motor.pinEn, OUTPUT); pinMode(motor.pinIN1, OUTPUT); pinMode(motor.pinIN2, OUTPUT); ledcAttachPin(motor.pinEn, PWMSpeedChannel); } moveCar(STOP); pinMode(LIGHT_PIN, OUTPUT); ledcAttachPin(LIGHT_PIN, PWMLightChannel); } void setup() { setUpPinModes(); Serial.begin(115200); WiFi.softAP(ssid, password); Serial.printf("AP IP address: %s\n", WiFi.softAPIP().toString().c_str()); server.on("/", HTTP_GET, handleRoot); server.onNotFound(handleNotFound); wsCamera.onEvent(onCameraWebSocketEvent); server.addHandler(&wsCamera); wsCarInput.onEvent(onCarInputWebSocketEvent); server.addHandler(&wsCarInput); server.begin(); Serial.println("HTTP server started"); setupCamera(); } void loop() { wsCamera.cleanupClients(); wsCarInput.cleanupClients(); sendCameraPicture(); Serial.printf("SPIRam Total heap %d, SPIRam Free Heap %d\n", ESP.getPsramSize(), ESP.getFreePsram()); }