Romeo ESP32-S3 Development Board Wiki - DFRobot

Introduction

The Romeo ESP32-S3 development board is a high-performance board meticulously designed for robotic projects. Embracing the ESP32-S3-WROOM-1U-N16R8 module, this board bestows formidable computational prowess and wireless communication capabilities upon robotic ventures. Notably, the Romeo ESP32-S3 is also equipped with a 4-channel 2.5A DC motor driver, eliminating the need for an additional motor driver board and enabling effortless robotic project creation. Additionally, this development board features a high-quality OV2640 camera, boasting a resolution of 2 million pixels and a 68° field of view. With support for resolutions of up to 1600*1200, it furnishes the robotic endeavor with a potent visual input device. Within the confines of the ESP32-S3-WROOM-1U-N16R8 module resides 16MB Flash and 8MB PSRAM, enabling ample storage for code and data. The integrated ESP32-S3 chip empowers the robot with formidable neural network computation and signal processing capabilities, elevating its cognitive faculties. The Romeo ESP32-S3 supports dual-mode communication, encompassing Wi-Fi and Bluetooth 5 (LE), thereby facilitating wireless robot control and image transmission functionalities. This board can be programmed through diverse environments, including Arduino IDE, ESP-IDF, and MicroPython, rendering hardware manipulation effortless with both C language and Python.

** Note: Before burning code, press and hold BOOT, click the reset button, and release BOOT to enter download mode. **

Features

Specification

Basic Parameters

Hardware Information

WIFI
蓝牙
Ports

Board Overview

Romeo ESP32-S3

Pin Diagram

GPIO Allocation Table

Motor Pin

PINS Romeo ESP32-S3 PINS
M1_EN/IN1 12
M1_PH/IN2 13
M2_EN/IN1 14
M2_PH/IN2 21
M3_EN/IN1 9
M3_PH/IN2 10
M4_EN/IN1 47
M4_PH/IN2 11

GDI Display Interface

This interface is a DFRbot dedicated GDI display interface for connecting a screen using a 18pin-FPC wire.

The pin list for using GDI camera interface is shown below:

FPC PINS Romeo ESP32-S3 PINS Description
VCC 3V3 3.3V
LCD_BL 21 Backlight
GND GND GND
SCLK 17/SCK SPI clock
MOSI 15/MOSI Host output, slave input
MISO 16/MISO Host input, slave output
LCD_DC 3 Data/command
LCD_RST 38 Reset
LCD_CS 18 TFT Chip Select
SD_CS 0 SD card chip select
FCS 7 Font library chip select
TCS 12 Touch chip select
SCL 2 I2C clock
SDA 1 I2C data
INT 13 INT
BUSY 14 Tearproof pins
X1 NC custom pin 1
X2 NC custom pin 2

When using FPC to connect the screen, please configure the corresponding pin numbers according to the GDL demo. Normally, only three pins need to be configured on different main controllers.

Displays that support GDI:

CAM接口

The CAM interface is compatible with both OV2640 and OV7725 camera. Enable AXP313A power output when using a camera. Click to download AXP313A library(ESP-IDF and MicroPython drivers are included).

The pin list for using DVP camera interface is shown below.

CAM PINS FireBeetle ESP32-S3 PINS Description
NC NC NC
AGND / Analog GND
SDA 1/SDA I2C data
AVDD / AXP313A Controllable Power
SCL 2/SCL I2C Clock
RST / Pulled up to DOVDD
VSYNC 6/A2 Frame sync signal
PWDN / Pulled down
HREF 42 Horizontal sync signal
DVDD / AXP313A Controllable Power
DOVDD / AXP313A Controllable Power
D9 48 DATA 9
XMCLK 45 Clock signal
D8 46 DATA 8
DGND GND Digital GND
D7 8/A3 DATA 7
PCLK 5/A1 Pixel Clock signal
D6 7/D5 DATA 6
D2 39 DATA 2
D5 4/A0 DATA 5
D3 40 DATA 3
D4 41 DATA 4
NC NC NC
NC NC NC

Pin connection

Connect the pin 1 of the camera to the white dot position

Sample code

See the FireBeetle ESP32-S3 tutorial for the basic tutorial.

EN/PH mode drives the motor

*PH/EN Control mode Truth Table *

EN PH OUT1 OUT2 说明
0 X L L Braking (low side slow attenuation)
1 0 L H retreat (OUT2 → OUT1)
1 1 H L advance (OUT1 → OUT2)

Drive dc motor

/**
 *@brief motorSpeeddetectionbyPH_EN.ino
 *@ Motor driver in PH/EN mode
 */
#include "driver/mcpwm.h"
#include "soc/mcpwm_struct.h" 
#include "soc/mcpwm_reg.h"

//IO12->M1_IN1
//IO13->M1_IN2
#define MOTOR_STEP_PIN 12 
#define MOTOR_DIRECTION_PIN 13

//Initialize the pins needed to generate the PWM signal
void mcpwm_init(void)
{
/**
 * @brief This function initializes each gpio signal for MCPWM
 *        @note
 *        This function initializes one gpio at a time.
 *
 * @param mcpwm_num set MCPWM unit(0-1)
 * @param io_signal set MCPWM signals, each MCPWM unit has 6 output(MCPWMXA, MCPWMXB) and 9 input(SYNC_X, FAULT_X, CAP_X)
 *                  'X' is timer_num(0-2)
 * @param gpio_num set this to configure gpio for MCPWM, if you want to use gpio16, gpio_num = 16
 *
 * @return
 *     - ESP_OK Success
 *     - ESP_ERR_INVALID_ARG Parameter error
 */
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0A,MOTOR_STEP_PIN);//The binding needs to output the PWM pin to the PWM channel
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0B,MOTOR_DIRECTION_PIN);

  //Configure mcpwm information
  mcpwm_config_t pwm_config;
  pwm_config.frequency = 1000;/*!<Set frequency of MCPWM in Hz*/
  pwm_config.cmpr_a = 0;/*!<Set % duty cycle for operator a(MCPWMXA), i.e for 62.3% duty cycle, duty_a = 62.3*/
  pwm_config.cmpr_b = 0;/*!<Set % duty cycle for operator b(MCPWMXB), i.e for 48% duty cycle, duty_b = 48.0*/
  pwm_config.counter_mode/*!<Set  type of MCPWM counter*/ = MCPWM_UP_COUNTER/*!<For asymmetric MCPWM*/; 
  pwm_config.duty_mode/*!<Set type of duty cycle*/ = MCPWM_DUTY_MODE_0/*!<Active high duty, i.e. duty cycle proportional to high time for asymmetric MCPWM*/;

/**
 * @brief Initialize MCPWM parameters
 *
 * @param mcpwm_num set MCPWM unit(0-1)
 * @param timer_num set timer number(0-2) of MCPWM, each MCPWM unit has 3 timers.
 * @param mcpwm_conf configure structure mcpwm_config_t
 *
 * @return
 *     - ESP_OK Success
 *     - ESP_ERR_INVALID_ARG Parameter error
 */  
  mcpwm_init(MCPWM_UNIT_0,MCPWM_TIMER_0,&pwm_config);//Initializes one of the mcpwm units and binds the clock
}

void advance(/*range:0~100*/uint8_t speed)
{

/**
 * @brief Use this function to set MCPWM signal high
 *
 * @param mcpwm_num set MCPWM unit(0-1)
 * @param timer_num set timer number(0-2) of MCPWM, each MCPWM unit has 3 timers
 * @param gen set the operator(MCPWMXA/MCPWMXB), 'x' is timer number selected
 * @return
 *     - ESP_OK Success
 *     - ESP_ERR_INVALID_ARG Parameter error
 */  
  mcpwm_set_signal_high(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B);//Give MOTOR_STEP_PIN a continuous high level

/**
 * @brief Set duty either active high or active low(out of phase/inverted)
 *        @note
 *        Call this function every time after mcpwm_set_signal_high or mcpwm_set_signal_low to resume with previously set duty cycle
 *
 * @param mcpwm_num set MCPWM unit(0-1)
 * @param timer_num set timer number(0-2) of MCPWM, each MCPWM unit has 3 timers
 * @param gen set the generator(MCPWMXA/MCPWMXB), 'x' is operator number selected
 * @param duty_type set active low or active high duty type
 *
 * @return
 *     - ESP_OK Success
 *     - ESP_ERR_INVALID_ARG Parameter error
 */  
  mcpwm_set_duty_type(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);

/**
 * @brief Set duty cycle of each operator(MCPWMXA/MCPWMXB)
 *
 * @param mcpwm_num set MCPWM unit(0-1)
 * @param timer_num set timer number(0-2) of MCPWM, each MCPWM unit has 3 timers
 * @param gen set the generator(MCPWMXA/MCPWMXB), 'X' is operator number selected
 * @param duty set duty cycle in %(i.e for 62.3% duty cycle, duty = 62.3) of each operator
 *
 * @return
 *     - ESP_OK Success
 *     - ESP_ERR_INVALID_ARG Parameter error
 */
  mcpwm_set_duty(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,speed);//The MOTOR_DIRECTION_PIN pin outputs a PWM wave with a duty cycle of "speed"
}

void retreat(/*range:0~100*/uint8_t speed)
{
  //Give MOTOR_STEP_PIN a continuous low level
  mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B);

  //The MOTOR_DIRECTION_PIN pin outputs a PWM wave with a duty cycle of "speed"
  mcpwm_set_duty_type(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
  mcpwm_set_duty(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,speed);
}

void breake(void)
{
  mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A);
}



void setup() {
  mcpwm_init();
}

void loop() {
  advance(70);
  delay(2000);
  retreat(30);
  delay(2000);
  breake();
  delay(2000);
}

Drive DC motor with encoder

The motor rotation speed is controlled by PID

/**
 *@brief motorSpeeddetectionbyPH_ENwithencoder.ino
 *@ Motor driver in PWM mode (with encoder)
 */
#include "driver/mcpwm.h"
#include "soc/mcpwm_struct.h" 
#include "soc/mcpwm_reg.h"
#include <PID_v1.h>

//IO12->M1_IN1
//IO13->M1_IN2
#define MOTOR_STEP_PIN 12 
#define MOTOR_DIRECTION_PIN 13

const byte encoder0pinA = 3;//A pin -> the interrupt pin 3
const byte encoder0pinB = 4;//B pin -> the digital pin 4
byte encoder0PinALast;
double duration,abs_duration;//the number of the pulses
boolean Direction;//the rotation direction
boolean result;
double val_output;//Used to provide PWM power values to the motor.
double Setpoint;
double Kp=0.6, Ki=5, Kd=0;
PID myPID(&abs_duration, &val_output, &Setpoint, Kp, Ki, Kd, DIRECT);

//Initialize the pins needed to generate the PWM signal
void mcpwm_init(void)
{
/**
 * @brief This function initializes each gpio signal for MCPWM
 *        @note
 *        This function initializes one gpio at a time.
 *
 * @param mcpwm_num set MCPWM unit(0-1)
 * @param io_signal set MCPWM signals, each MCPWM unit has 6 output(MCPWMXA, MCPWMXB) and 9 input(SYNC_X, FAULT_X, CAP_X)
 *                  'X' is timer_num(0-2)
 * @param gpio_num set this to configure gpio for MCPWM, if you want to use gpio16, gpio_num = 16
 *
 * @return
 *     - ESP_OK Success
 *     - ESP_ERR_INVALID_ARG Parameter error
 */  
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0A,MOTOR_STEP_PIN);//The binding needs to output the PWM pin to the PWM channel
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0B,MOTOR_DIRECTION_PIN);

  //Configure mcpwm information
  mcpwm_config_t pwm_config;
  pwm_config.frequency = 1000;/*!<Set frequency of MCPWM in Hz*/
  pwm_config.cmpr_a = 0;/*!<Set % duty cycle for operator a(MCPWMXA), i.e for 62.3% duty cycle, duty_a = 62.3*/
  pwm_config.cmpr_b = 0;/*!<Set % duty cycle for operator b(MCPWMXB), i.e for 48% duty cycle, duty_b = 48.0*/
  pwm_config.counter_mode/*!<Set  type of MCPWM counter*/ = MCPWM_UP_COUNTER/*!<For asymmetric MCPWM*/; 
  pwm_config.duty_mode/*!<Set type of duty cycle*/ = MCPWM_DUTY_MODE_0/*!<Active high duty, i.e. duty cycle proportional to high time for asymmetric MCPWM*/;

/**
 * @brief Initialize MCPWM parameters
 *
 * @param mcpwm_num set MCPWM unit(0-1)
 * @param timer_num set timer number(0-2) of MCPWM, each MCPWM unit has 3 timers.
 * @param mcpwm_conf configure structure mcpwm_config_t
 *
 * @return
 *     - ESP_OK Success
 *     - ESP_ERR_INVALID_ARG Parameter error
 */    
  mcpwm_init(MCPWM_UNIT_0,MCPWM_TIMER_0,&pwm_config);//Initializes one of the mcpwm units and binds the clock
}

void advance(/*range:0~100*/uint8_t speed)
{
/**
 * @brief Use this function to set MCPWM signal high
 *
 * @param mcpwm_num set MCPWM unit(0-1)
 * @param timer_num set timer number(0-2) of MCPWM, each MCPWM unit has 3 timers
 * @param gen set the operator(MCPWMXA/MCPWMXB), 'x' is timer number selected
 * @return
 *     - ESP_OK Success
 *     - ESP_ERR_INVALID_ARG Parameter error
 */    
  mcpwm_set_signal_high(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B);//Give MOTOR_STEP_PIN a continuous high level

/**
 * @brief Set duty either active high or active low(out of phase/inverted)
 *        @note
 *        Call this function every time after mcpwm_set_signal_high or mcpwm_set_signal_low to resume with previously set duty cycle
 *
 * @param mcpwm_num set MCPWM unit(0-1)
 * @param timer_num set timer number(0-2) of MCPWM, each MCPWM unit has 3 timers
 * @param gen set the generator(MCPWMXA/MCPWMXB), 'x' is operator number selected
 * @param duty_type set active low or active high duty type
 *
 * @return
 *     - ESP_OK Success
 *     - ESP_ERR_INVALID_ARG Parameter error
 */    
  mcpwm_set_duty_type(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);

/**
 * @brief Set duty cycle of each operator(MCPWMXA/MCPWMXB)
 *
 * @param mcpwm_num set MCPWM unit(0-1)
 * @param timer_num set timer number(0-2) of MCPWM, each MCPWM unit has 3 timers
 * @param gen set the generator(MCPWMXA/MCPWMXB), 'X' is operator number selected
 * @param duty set duty cycle in %(i.e for 62.3% duty cycle, duty = 62.3) of each operator
 *
 * @return
 *     - ESP_OK Success
 *     - ESP_ERR_INVALID_ARG Parameter error
 */  
  mcpwm_set_duty(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,speed);//The MOTOR_DIRECTION_PIN pin outputs a PWM wave with a duty cycle of "speed"
}

void retreat(/*range:0~100*/uint8_t speed)
{
  //Give MOTOR_STEP_PIN a continuous low level
  mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B);

  //The MOTOR_DIRECTION_PIN pin outputs a PWM wave with a duty cycle of "speed"
  mcpwm_set_duty_type(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
  mcpwm_set_duty(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,speed);
}

void breake(void)
{
  mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A);
//  mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B);
}

void wheelSpeed()
{
  int Lstate = digitalRead(encoder0pinA);
  if((encoder0PinALast == LOW) && Lstate==HIGH)
  {
    int val = digitalRead(encoder0pinB);
    if(val == LOW && Direction)
    {
      Direction = false; //Reverse
    }
    else if(val == HIGH && !Direction)
    {
      Direction = true;  //Forward
    }
  }
  encoder0PinALast = Lstate;

  if(!Direction)  
    duration++;
  else  
    duration--;
}

void EncoderInit()
{
  Direction = true;//default -> Forward
  pinMode(encoder0pinB,INPUT);
  attachInterrupt(digitalPinToInterrupt(encoder0pinA), wheelSpeed, CHANGE);
}

void setup() {
  Serial.begin(9600);//Initialize the serial port
  mcpwm_init();
  advance(70);
  Setpoint =80;  //Set the output value of PID
  myPID.SetMode(AUTOMATIC);//Set PID to automatic mode
  myPID.SetSampleTime(100);//Set the PID sampling frequency to 100ms
  EncoderInit();//Initialize the module
}

void loop() {
  abs_duration=abs(duration);
  result=myPID.Compute();//The return value of PID conversion is 1
  if(result)
  {
    Serial.print("Pluse: ");
    Serial.println(duration);
    duration = 0; //Count clear and wait for the next count
  }  
}

PWM mode drives the motor

Truth table of PWM control mode

IN1 IN2 OUT1 OUT2 explain
0 0 Hi-Z Hi-Z Taxiing (H-bridge high impedance)
0 1 L H retreat (OUT2 → OUT1)
1 0 H L advance (OUT1 → OUT2)
1 1 L L Braking (low side slow attenuation)

Drive dc motor

/**
 *@brief motorSpeeddetectionbyPWM.ino
 *@ Motor driver in PWM mode
 */
#include "driver/mcpwm.h"
#include "soc/mcpwm_struct.h" 
#include "soc/mcpwm_reg.h"

//IO12->M1_IN1
//IO13->M1_IN2
#define MOTOR_PWM_IN1 12 
#define MOTOR_PWM_IN2 13

//Initialize the pins needed to generate the PWM signal
void mcpwm_init(void)
{
  // Binding needs to output the PWM pin to the PWM channel
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0A,MOTOR_PWM_IN1);
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0B,MOTOR_PWM_IN2);

  //Configure mcpwm information
  mcpwm_config_t pwm_config;
  pwm_config.frequency = 1000;/*!<Set frequency of MCPWM in Hz*/
  pwm_config.cmpr_a = 0;/*!<Set % duty cycle for operator a(MCPWMXA), i.e for 62.3% duty cycle, duty_a = 62.3*/
  pwm_config.cmpr_b = 0;/*!<Set % duty cycle for operator b(MCPWMXB), i.e for 48% duty cycle, duty_b = 48.0*/
  pwm_config.counter_mode/*!<Set  type of MCPWM counter*/ = MCPWM_UP_COUNTER/*!<For asymmetric MCPWM*/; 
  pwm_config.duty_mode/*!<Set type of duty cycle*/ = MCPWM_DUTY_MODE_0/*!<Active high duty, i.e. duty cycle proportional to high time for asymmetric MCPWM*/;

  //Initialize a unit of mcpwm and bind the clock
  mcpwm_init(MCPWM_UNIT_0,MCPWM_TIMER_0,&pwm_config);
}

void advance(/*range:0~100*/uint8_t speed)
{
  mcpwm_set_duty_type(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
  mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B);
  mcpwm_set_duty(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,speed);
}

void retreat(/*range:0~100*/uint8_t speed)
{
  //Give MOTOR_DIRECTION_PIN a continuous low level
  mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A);

  /*
   * Call function mcpwm_set_duty_type() every time after mcpwm_set_signal_high() 
   * or mcpwm_set_signal_low() to resume with previously set duty cycle.
   */
  mcpwm_set_duty_type(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B,MCPWM_DUTY_MODE_0);

  //The MOTOR_STEP_PIN pin outputs a PWM wave with a duty cycle of "speed"
  mcpwm_set_duty(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B,speed);
}

void stop(void)
{
  mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A);
  mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B);
}

void breake(void)
{
  mcpwm_set_signal_high(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A);
  mcpwm_set_signal_high(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B);
}

void setup() {
  mcpwm_init();
}

void loop() {
  advance(30);
  delay(2000);
  retreat(60);
  delay(2000);
  stop();
  delay(2000);
  advance(30);
  delay(2000);
  retreat(60);
  delay(2000);
  breake();
  delay(2000);
}

Drive DC motor with encoder

The motor rotation speed is controlled by PID

/**
 *@brief motorSpeeddetectionbyPWMwithencoder.ino
 *@ Motor driver in PWM mode (with encoder)
 */
#include "driver/mcpwm.h"
#include "soc/mcpwm_struct.h" 
#include "soc/mcpwm_reg.h"
#include <PID_v1.h>

//IO12->M1_IN1
//IO13->M1_IN2
#define MOTOR_PWM_IN1 12 
#define MOTOR_PWM_IN2 13

const byte encoder0pinA = 3;//A pin -> the interrupt pin 3
const byte encoder0pinB = 4;//B pin -> the digital pin 4
byte encoder0PinALast;
double duration,abs_duration;//the number of the pulses
boolean Direction;//the rotation direction
boolean result;
double val_output;//Used to provide PWM power values to the motor.
double Setpoint;
double Kp=0.6, Ki=5, Kd=0;
PID myPID(&abs_duration, &val_output, &Setpoint, Kp, Ki, Kd, DIRECT);

//Initialize the pins needed to generate the PWM signal
void mcpwm_init(void)
{
  //The binding needs to output the PWM pin to the PWM channel
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0A,MOTOR_PWM_IN1);
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0B,MOTOR_PWM_IN2);

  //Configure mcpwm information
  mcpwm_config_t pwm_config;
  pwm_config.frequency = 1000;/*!<Set frequency of MCPWM in Hz*/
  pwm_config.cmpr_a = 0;/*!<Set % duty cycle for operator a(MCPWMXA), i.e for 62.3% duty cycle, duty_a = 62.3*/
  pwm_config.cmpr_b = 0;/*!<Set % duty cycle for operator b(MCPWMXB), i.e for 48% duty cycle, duty_b = 48.0*/
  pwm_config.counter_mode/*!<Set  type of MCPWM counter*/ = MCPWM_UP_COUNTER/*!<For asymmetric MCPWM*/; 
  pwm_config.duty_mode/*!<Set type of duty cycle*/ = MCPWM_DUTY_MODE_0/*!<Active high duty, i.e. duty cycle proportional to high time for asymmetric MCPWM*/;

  // Initializes a unit of mcpwm and binds the clock
  mcpwm_init(MCPWM_UNIT_0,MCPWM_TIMER_0,&pwm_config);
}


void advance(/*range:0~100*/uint8_t speed)
{
  mcpwm_set_duty_type(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
  mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B);
  mcpwm_set_duty(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,speed);
}

void retreat(/*range:0~100*/uint8_t speed)
{
  //Give MOTOR_DIRECTION_PIN a continuous low level
  mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A);

  /*
   * Call function mcpwm_set_duty_type() every time after mcpwm_set_signal_high() 
   * or mcpwm_set_signal_low() to resume with previously set duty cycle.
   */
  mcpwm_set_duty_type(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B,MCPWM_DUTY_MODE_0);

  //The MOTOR_STEP_PIN pin outputs a PWM wave with a duty cycle of "speed"
  mcpwm_set_duty(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B,speed);
}

void stop(void)
{
  mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A);
  mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B);
}

void breake(void)
{
  mcpwm_set_signal_high(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A);
  mcpwm_set_signal_high(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B);
}

void wheelSpeed()
{
  int Lstate = digitalRead(encoder0pinA);
  if((encoder0PinALast == LOW) && Lstate==HIGH)
  {
    int val = digitalRead(encoder0pinB);
    if(val == LOW && Direction)
    {
      Direction = false; //Reverse
    }
    else if(val == HIGH && !Direction)
    {
      Direction = true;  //Forward
    }
  }
  encoder0PinALast = Lstate;

  if(!Direction)  
    duration++;
  else  
    duration--;
}

void EncoderInit()
{
  Direction = true;//default -> Forward
  pinMode(encoder0pinB,INPUT);
  attachInterrupt(digitalPinToInterrupt(encoder0pinA), wheelSpeed, CHANGE);
}

void setup() {
  Serial.begin(115200);//Initialize the serial port
  mcpwm_init();
  advance(70);
  Setpoint =80;  //Set the output value of PID
  myPID.SetMode(AUTOMATIC);//Set PID to automatic mode
  myPID.SetSampleTime(100);//Set the PID sampling frequency to 100ms
  EncoderInit();//Initialize the module
}

void loop() {
  abs_duration=abs(duration);
  result=myPID.Compute();//The return value of PID conversion is 1
  if(result)
  {
    Serial.print("Pluse: ");
    Serial.println(duration);
    duration = 0; //Count clear and wait for the next count
  }  
}

Drive car practice

Connect the hardware according to the wiring diagram, burn the code, connect "ESP32 S3 Romeo", enter 192.168.4.1 in the browser to drive the car and view the camera data

Please download and install before use

#include "esp_camera.h"
#include <Arduino.h>
#include <WiFi.h>
#include <AsyncTCP.h>
#include <ESPAsyncWebServer.h>
#include <iostream>
#include <sstream>
#include "DFRobot_AXP313A.h"
#include "driver/mcpwm.h"
#include "soc/mcpwm_struct.h" 
#include "soc/mcpwm_reg.h"

DFRobot_AXP313A axp;

#define M1_EN 12
#define M1_PN 13
#define M2_EN 14
#define M2_PN 21
#define M3_EN 9
#define M3_PN 10
#define M4_EN 47
#define M4_PN 11


#define UP 1
#define DOWN 2
#define LEFT 3
#define RIGHT 4
#define STOP 0

#define FORWARD 1
#define BACKWARD -1

//Camera related constants
#define PWDN_GPIO_NUM     -1
#define RESET_GPIO_NUM    -1
#define XCLK_GPIO_NUM     45
#define SIOD_GPIO_NUM     1
#define SIOC_GPIO_NUM     2

#define Y9_GPIO_NUM       48
#define Y8_GPIO_NUM       46
#define Y7_GPIO_NUM       8
#define Y6_GPIO_NUM       7
#define Y5_GPIO_NUM       4
#define Y4_GPIO_NUM       41
#define Y3_GPIO_NUM       40
#define Y2_GPIO_NUM       39
#define VSYNC_GPIO_NUM    6
#define HREF_GPIO_NUM     42
#define PCLK_GPIO_NUM     5

const char* ssid     = "ESP32 S3 Romeo";
const char* password = "12345678";

AsyncWebServer server(80);
AsyncWebSocket wsCamera("/Camera");
AsyncWebSocket wsCarInput("/CarInput");
uint32_t cameraClientId = 0;

uint8_t Speed = 50;

const char* htmlHomePage PROGMEM = R"HTMLHOMEPAGE(
<!DOCTYPE html>
<html>
  <head>
  <meta name="viewport" content="width=device-width, initial-scale=1, maximum-scale=1, user-scalable=no">
    <style>
    .arrows {
      font-size:30px;
      color:red;
    }
    td.button {
      background-color:black;
      border-radius:25%;
      box-shadow: 5px 5px #888888;
    }
    td.button:active {
      transform: translate(5px,5px);
      box-shadow: none; 
    }

    .noselect {
      -webkit-touch-callout: none; /* iOS Safari */
        -webkit-user-select: none; /* Safari */
         -khtml-user-select: none; /* Konqueror HTML */
           -moz-user-select: none; /* Firefox */
            -ms-user-select: none; /* Internet Explorer/Edge */
                user-select: none; /* Non-prefixed version, currently
                                      supported by Chrome and Opera */
    }

    .slidecontainer {
      width: 100%;
    }

    .slider {
      -webkit-appearance: none;
      width: 100%;
      height: 15px;
      border-radius: 5px;
      background: #d3d3d3;
      outline: none;
      opacity: 0.7;
      -webkit-transition: .2s;
      transition: opacity .2s;
    }

    .slider:hover {
      opacity: 1;
    }

    .slider::-webkit-slider-thumb {
      -webkit-appearance: none;
      appearance: none;
      width: 25px;
      height: 25px;
      border-radius: 50%;
      background: red;
      cursor: pointer;
    }

    .slider::-moz-range-thumb {
      width: 25px;
      height: 25px;
      border-radius: 50%;
      background: red;
      cursor: pointer;
    }

    </style>

  </head>
  <body class="noselect" align="center" style="background-color:white">
    <table id="mainTable" style="width:400px;margin:auto;table-layout:fixed" CELLSPACING=10>
      <tr>
        <img id="cameraImage" src="" style="width:400px;height:250px"></td>
      </tr> 
      <tr>
        <td></td>
        <td class="button" ontouchstart='sendButtonInput("MoveCar","1")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >⇧</span></td>
        <td></td>
      </tr>
      <tr>
        <td class="button" ontouchstart='sendButtonInput("MoveCar","3")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >⇦</span></td>
        <td class="button"></td>    
        <td class="button" ontouchstart='sendButtonInput("MoveCar","4")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >⇨</span></td>
      </tr>
      <tr>
        <td></td>
        <td class="button" ontouchstart='sendButtonInput("MoveCar","2")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >⇩</span></td>
        <td></td>
      </tr>
      <tr/><tr/>
      <tr>
        <td style="text-align:left"><b>Speed:</b></td>
        <td colspan=2>
         <div class="slidecontainer">
            <input type="range" min="0" max="100" value="50" class="slider" id="Speed" oninput='sendButtonInput("Speed",value)'>
          </div>
        </td>
      </tr>        

    </table>

    <script>
      var webSocketCameraUrl = "ws:\/\/" + window.location.hostname + "/Camera";
      var webSocketCarInputUrl = "ws:\/\/" + window.location.hostname + "/CarInput";      
      var websocketCamera;
      var websocketCarInput;

      function initCameraWebSocket() 
      {
        websocketCamera = new WebSocket(webSocketCameraUrl);
        websocketCamera.binaryType = 'blob';
        websocketCamera.onopen    = function(event){};
        websocketCamera.onclose   = function(event){setTimeout(initCameraWebSocket, 2000);};
        websocketCamera.onmessage = function(event)
        {
          var imageId = document.getElementById("cameraImage");
          imageId.src = URL.createObjectURL(event.data);
        };
      }

      function initCarInputWebSocket() 
      {
        websocketCarInput = new WebSocket(webSocketCarInputUrl);
        websocketCarInput.onopen    = function(event)
        {
          sendButtonInput("Speed", document.getElementById("Speed").value);

        };
        websocketCarInput.onclose   = function(event){setTimeout(initCarInputWebSocket, 2000);};
        websocketCarInput.onmessage = function(event){};        
      }

      function initWebSocket() 
      {
        initCameraWebSocket ();
        initCarInputWebSocket();
      }

      function sendButtonInput(key, value) 
      {
        var data = key + "," + value;
        websocketCarInput.send(data);
      }

      window.onload = initWebSocket;
      document.getElementById("mainTable").addEventListener("touchend", function(event){
        event.preventDefault()
      });      
    </script>
  </body>    
</html>
)HTMLHOMEPAGE";


void advance(uint8_t motorNumber,uint8_t speed)
{
  switch(motorNumber)
  {
    case 1:
      mcpwm_set_signal_high(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B);//Give PH a consistently high level
      mcpwm_set_duty_type(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
      mcpwm_set_duty(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,speed);//The EN pin outputs a PWM wave with a duty cycle of "speed"
      break;

    case 2:
      mcpwm_set_signal_high(MCPWM_UNIT_0,MCPWM_TIMER_1,MCPWM_GEN_B);//Give PH a consistently high level
      mcpwm_set_duty_type(MCPWM_UNIT_0,MCPWM_TIMER_1,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
      mcpwm_set_duty(MCPWM_UNIT_0,MCPWM_TIMER_1,MCPWM_GEN_A,speed);//The EN pin outputs a PWM wave with a duty cycle of "speed"
      break;

    case 3:
      mcpwm_set_signal_high(MCPWM_UNIT_1,MCPWM_TIMER_0,MCPWM_GEN_B);//Give PH a consistently high level
      mcpwm_set_duty_type(MCPWM_UNIT_1,MCPWM_TIMER_0,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
      mcpwm_set_duty(MCPWM_UNIT_1,MCPWM_TIMER_0,MCPWM_GEN_A,speed);//The EN pin outputs a PWM wave with a duty cycle of "speed"
      break;

    case 4:
      mcpwm_set_signal_high(MCPWM_UNIT_1,MCPWM_TIMER_1,MCPWM_GEN_B);//Give PH a consistently high level
      mcpwm_set_duty_type(MCPWM_UNIT_1,MCPWM_TIMER_1,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
      mcpwm_set_duty(MCPWM_UNIT_1,MCPWM_TIMER_1,MCPWM_GEN_A,speed);//The EN pin outputs a PWM wave with a duty cycle of "speed"
      break;
  }
}

void retreat(uint8_t motorNumber,uint8_t speed)
{
  switch(motorNumber)
  {
    case 1:
      mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B);//Give PH a constant low level
      mcpwm_set_duty_type(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
      mcpwm_set_duty(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,speed);//The EN pin outputs a PWM wave with a duty cycle of "speed"
      break;

    case 2:
      mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_1,MCPWM_GEN_B);//Give PH a constant low level
      mcpwm_set_duty_type(MCPWM_UNIT_0,MCPWM_TIMER_1,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
      mcpwm_set_duty(MCPWM_UNIT_0,MCPWM_TIMER_1,MCPWM_GEN_A,speed);//The EN pin outputs a PWM wave with a duty cycle of "speed"
      break;

    case 3:
      mcpwm_set_signal_low(MCPWM_UNIT_1,MCPWM_TIMER_0,MCPWM_GEN_B);//Give PH a constant low level
      mcpwm_set_duty_type(MCPWM_UNIT_1,MCPWM_TIMER_0,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
      mcpwm_set_duty(MCPWM_UNIT_1,MCPWM_TIMER_0,MCPWM_GEN_A,speed);//The EN pin outputs a PWM wave with a duty cycle of "speed"
      break;

    case 4:
      mcpwm_set_signal_low(MCPWM_UNIT_1,MCPWM_TIMER_1,MCPWM_GEN_B);//Give PH a constant low level
      mcpwm_set_duty_type(MCPWM_UNIT_1,MCPWM_TIMER_1,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
      mcpwm_set_duty(MCPWM_UNIT_1,MCPWM_TIMER_1,MCPWM_GEN_A,speed);//The EN pin outputs a PWM wave with a duty cycle of "speed"
      break;
  }
}

void breake(uint8_t motorNumber)
{
  switch(motorNumber)
  {
    case 1:
      mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A);
      break;

    case 2:
      mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_1,MCPWM_GEN_A);
      break;

    case 3:
      mcpwm_set_signal_low(MCPWM_UNIT_1,MCPWM_TIMER_0,MCPWM_GEN_A);
      break;

    case 4:
      mcpwm_set_signal_low(MCPWM_UNIT_1,MCPWM_TIMER_1,MCPWM_GEN_A);
      break;
  }
}

void moveCar(uint8_t inputValue,uint8_t speed)
{
  switch(inputValue)
  {
    case UP:
      advance(1,speed);
      advance(2,speed);
      advance(3,speed);
      advance(4,speed);
      break;

    case DOWN:
      retreat(1,speed);
      retreat(2,speed);
      retreat(3,speed);
      retreat(4,speed);
      break;

    case LEFT:
      advance(2,speed);
      advance(4,speed);
      retreat(1,speed);
      retreat(3,speed);
      break;

    case RIGHT:
      advance(1,speed);
      advance(3,speed);
      retreat(2,speed);
      retreat(4,speed);
      break;

    case STOP:
      breake(1);
      breake(2);
      breake(3);
      breake(4);
      break;
  }
}

void handleRoot(AsyncWebServerRequest *request) 
{
  request->send_P(200, "text/html", htmlHomePage);
}

void handleNotFound(AsyncWebServerRequest *request) 
{
    request->send(404, "text/plain", "File Not Found");
}

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(STOP,0);
      //ledcWrite(PWMLightChannel, 0); 
      //panServo.write(90);
      //tiltServo.write(90);       
      break;
    case WS_EVT_DATA:
      AwsFrameInfo *info;
      info = (AwsFrameInfo*)arg;
      if (info->final && info->index == 0 && info->len == len && info->opcode == WS_TEXT) 
      {
        std::string myData = "";
        myData.assign((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,Speed);        
        }
        else if (key == "Speed")
        {
          Speed = valueInt;
        }
        /*else if (key == "Light")
        {
          //ledcWrite(PWMLightChannel, valueInt);         
        }
        else if (key == "Pan")
        {
          //panServo.write(valueInt);
        }
        else if (key == "Tilt")
        {
          //tiltServo.write(valueInt);   
        }  */           
      }
      break;
    case WS_EVT_PONG:
    case WS_EVT_ERROR:
      break;
    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:
      break;
    case WS_EVT_PONG:
    case WS_EVT_ERROR:
      break;
    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.frame_size = FRAMESIZE_UXGA;
  config.pixel_format = PIXFORMAT_JPEG; // for streaming
  //config.pixel_format = PIXFORMAT_RGB565; // for face detection/recognition
  config.grab_mode = CAMERA_GRAB_WHEN_EMPTY;
  config.fb_location = CAMERA_FB_IN_PSRAM;
  config.jpeg_quality = 12;
  config.fb_count = 1;

    // if PSRAM IC present, init with UXGA resolution and higher JPEG quality
  //                      for larger pre-allocated frame buffer.
  if(config.pixel_format == PIXFORMAT_JPEG){
    if(psramFound()){
      config.jpeg_quality = 10;
      config.fb_count = 2;
      config.grab_mode = CAMERA_GRAB_LATEST;
    } else {
      // Limit the frame size when PSRAM is not available
      config.frame_size = FRAMESIZE_SVGA;
      config.fb_location = CAMERA_FB_IN_DRAM;
    }
  } else {
    // Best option for face detection/recognition
    config.frame_size = FRAMESIZE_240X240;
#if CONFIG_IDF_TARGET_ESP32S3
    config.fb_count = 2;
#endif
  }


  // 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;
  }  

  if (psramFound())
  {
    heap_caps_malloc_extmem_enable(20000);  
    Serial.printf("PSRAM initialized. malloc to take memory from psram above this size");    
  }  
}

void sendCameraPicture()
{
  if (cameraClientId == 0)
  {
    return;
  }
  unsigned long  startTime1 = millis();
  //capture a frame
  camera_fb_t * fb = esp_camera_fb_get();
  if (!fb) 
  {
      Serial.println("Frame buffer could not be acquired");
      return;
  }

  unsigned long  startTime2 = millis();
  wsCamera.binary(cameraClientId, fb->buf, fb->len);
  esp_camera_fb_return(fb);

  //Wait for message to be delivered
  while (true)
  {
    AsyncWebSocketClient * clientPointer = wsCamera.client(cameraClientId);
    if (!clientPointer || !(clientPointer->queueIsFull()))
    {
      break;
    }
    delay(1);
  }

  unsigned long  startTime3 = millis();  
  Serial.printf("Time taken Total: %d|%d|%d\n",startTime3 - startTime1, startTime2 - startTime1, startTime3-startTime2 );
}

//Initialize the pins needed to generate the PWM signal
void mcpwm_init(void)
{
  //Configure mcpwm information
  mcpwm_config_t pwm_config;
  pwm_config.frequency = 1000;
  pwm_config.cmpr_a = 0;
  pwm_config.cmpr_b = 0;
  pwm_config.counter_mode = MCPWM_UP_COUNTER;
  pwm_config.duty_mode = MCPWM_DUTY_MODE_0;

  //A speed B direction
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0A,M1_EN);//Motor 1 GPIO
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0B,M1_PN);
  mcpwm_init(MCPWM_UNIT_0,MCPWM_TIMER_0,&pwm_config);//Initializes a unit of mcpwm and binds the clock

  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM1A,M2_EN);//Motor 2 GPIO
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM1B,M2_PN);
  mcpwm_init(MCPWM_UNIT_0,MCPWM_TIMER_1,&pwm_config);//Initializes a unit of mcpwm and binds the clock

  mcpwm_gpio_init(MCPWM_UNIT_1,MCPWM0A,M3_EN);//Motor 3 GPIO
  mcpwm_gpio_init(MCPWM_UNIT_1,MCPWM0B,M3_PN);
  mcpwm_init(MCPWM_UNIT_1,MCPWM_TIMER_0,&pwm_config);//Initializes a unit of mcpwm and binds the clock

  mcpwm_gpio_init(MCPWM_UNIT_1,MCPWM1A,M4_EN);//Motor 4 GPIO
  mcpwm_gpio_init(MCPWM_UNIT_1,MCPWM1B,M4_PN);
  mcpwm_init(MCPWM_UNIT_1,MCPWM_TIMER_1,&pwm_config);//Initializes a unit of mcpwm and binds the clock
}


void setup(void) 
{
  Serial.begin(115200);
  while(axp.begin() != 0){
    Serial.println("init error");
    delay(1000);
  }
  axp.enableCameraPower(axp.eOV2640);//Set up camera power supply
  mcpwm_init();

  WiFi.softAP(ssid, password);
  IPAddress IP = WiFi.softAPIP();
  Serial.print("AP IP address: ");
  Serial.println(IP);

  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());
}

FAQ

1. What will cause burning error?

How to solve

2. Data cannot be printed on serial port

For any questions, advice or cool ideas to share, please visit the DFRobot Forum.

More Documents

DFshopping_car1.png Get Romeo ESP32 S3 from DFRobot Store or DFRobot Distributor.

Turn to the Top