Beetle ESP32-C3

1.Romeo ESP32-S3简介

Romeo ESP32-S3开发板是专为机器人项目设计的高性能开发板。该开发板搭载了ESP32-S3-WROOM-1U-N16R8模组,为机器人项目提供强大的计算能力和无线通讯功能。同时,Romeo ESP32-S3还配备了4路2.5A直流电机驱动,无需额外添加电机驱动板即可轻松制作机器人项目。

该开发板配备了一颗高品质的OV2640摄像头,拥有200万像素和68°视场角,支持最高1600*1200分辨率,为机器人提供了视觉输入设备。

ESP32-S3-WROOM-1U-N16R8模组内置16MB Flash和8MB PSRAM,可存储更多代码和数据。其搭载的ESP32-S3芯片具备强大的神经网络运算和信号处理能力,使机器人更加智能。

Romeo ESP32-S3支持Wi-Fi和Bluetooth 5 (LE)双模通讯,可实现无线控制机器人和图像传输的功能。

可以在Arduino IDE、ESP-IDF、MicroPython等环境下对Romeo ESP32-S3进行编程,C语言、python都可以轻松的操纵硬件。

注意:烧录代码前,请按住BOOT,点击复位按键,然后松开BOOT使开发板进入下载模式

2.产品特性

  • 四路2.5A大电流H桥电机驱动
  • 支持PH/EN控制模式和PWM控制模式
  • 多路5V电源输出,方便驱动舵机
  • 独立摄像头供电电路
  • 板载GDI显示、DVP摄像头、USB、MicroSD卡接口
  • 板载ESP32-S3-1U-N16R8 (16MB FLASH / 8MB PSRAM)
  • 支持Wi-Fi 和 Bluetooth 5 (LE) 双模通讯

3.产品参数

基本参数

  • Type-C输入电压: 5V DC
  • 模组工作电压: 3.3V
  • VIN输入电压:7-24V
  • VM输入电压:5-24V
  • 5V电源最大输出电流:2A
  • 电机驱动能力:2.5A
  • 工作温度:0~60℃
  • 模块尺寸:75*90mm

硬件信息

  • 处理器:Xtensa® 双核32位LX7微处理器
  • 主频:240 MHz
  • SRAM:512KB
  • ROM:384KB
  • Flash:16MB
  • PSRAM: 8MB
  • RTC SRAM:16KB
  • USB: USB 2.0 OTG全速接口
WIFI
  • WIFI协议:IEEE 802.11b/g/n
  • WIFI频宽: 2.4 GHz 频带支持 20 MHz 和 40 MHz 频宽
  • WIFI模式:Station 模式、SoftAP 模式、SoftAP+Station 模式和混杂模式
  • WIFI频率:2.4GHz
  • 帧聚合: TX/RX A-MPDU, TX/RX A-MSDU
蓝牙
  • 蓝牙协议:Bluetooth 5、Bluetooth mesh
  • 蓝牙频率:125 Kbps、500 Kbps、1 Mbps、2 Mbps
接口引脚
  • 数字I/O x27
  • LED PWM 控制器 8个通道
  • SPI x2
  • UART x3
  • I2C x2
  • I2S x2
  • 红外收发器:发送通道 x5、接收通道 x5
  • 2 × 12 位 SAR ADC, 20个通道
  • DMA 控制器,5 个接收通道和 5 个发送通道

4.板载资源示意

Romeo ESP32-S3

  • Type-C:5V输入
  • 5V:5V电源输出
  • VIN:7-24V, 主控电源输入
  • VM:5-24V, 电机电源输入
  • JP1:电源切换跳线帽,短接时控制器和电机共用电源
  • SW:电源控制开关
  • PMODE: 电机驱动模式跳线帽,短接时为PH/EN控制模式,断开时为PWM控制模式
  • Motor:电机接线端子
  • ESP32-S3模组:乐鑫公司推出的ESP32-S3模组
  • M1EN/M1PH:M1电机驱动跳线
  • M2EN/M2PH:M2电机驱动跳线
  • RST:复位按键
  • BOOT:BOOT按键
  • AXP313A:电源管理芯片
  • GDI:GDI显示屏接口
  • CAM:DVP摄像头接口
  • USB:USB接口,可接USB外设
  • MicroSD:TF卡卡槽

5.引脚概述

GPIO分配表

电机引脚

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显示接口

此接口为DFRbot专用GDI显示屏接口,使用18pin-FPC线连接连接屏幕,连接屏幕更加便捷。

以下是GDI接口使用的引脚列表

FPC PINS Romeo ESP32-S3 PINS Description
VCC 3V3 3.3V
LCD_BL 21 背光
GND GND GND
SCLK 17/SCK SPI时钟
MOSI 15/MOSI 主机输出,从机输入
MISO 16/MISO 主机输入,从机输出
LCD_DC 3 数据/命令
LCD_RST 38 复位
LCD_CS 18 TFT片选
SD_CS 0 SD卡片选
FCS 7 字库片选
TCS 12 触摸片选
SCL 2 I2C时钟
SDA 1 I2C数据
INT 13 INT
BUSY 14 防撕裂引脚
X1 NC 自定义引脚1
X2 NC 自定义引脚2

使用FPC链接屏幕时根据GDL demo配置所需对应的引脚号即可,通常只需要根据不同主控配置三个引脚

支持GDI的显示屏:

CAM接口

此接口为DVP摄像头接口,兼容OV2640和OV7725摄像头

以下是DVP摄像头接口使用的引脚列表

注意:使用摄像头时需使用”axp.enableCameraPower(axp.eOV2640);“打开摄像头电源

CAM PINS Romeo ESP32-S3 PINS Description
NC NC NC
AGND / 模拟地
SDA 1/SDA I2C数据
AVDD / AXP313A可控电源
SCL 2/SCL I2C时钟
RST / 已上拉到DOVDD
VSYNC 6/A2 帧同步信号
PWDN / 已下拉
HREF 42 行同步信号
DVDD / AXP313A可控电源
DOVDD / AXP313A可控电源
D9 48 DATA 9
XMCLK 45 时钟信号
D8 46 DATA 8
DGND GND 数字地
D7 8/A3 DATA 7
PCLK 5/A1 像素时钟信号
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

6.示例代码

基础使用教程请看FireBeetle ESP32-S3教程

6.1 EN/PH模式驱动电机

PH/EN 控制模式真值表

EN PH OUT1 OUT2 说明
0 X L L 制动(低侧慢速衰减)
1 0 L H 后退 (OUT2 → OUT1)
1 1 H L 前进 (OUT1 → OUT2)

6.1.1 驱动直流电机

/**
 *@brief motorSpeeddetectionbyPH_EN.ino
 *@ 在PH/EN模式下的电机驱动程序
 */
#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

//初始化需要产生PWM信号的引脚
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);//绑定需要输出PWM的引脚到PWM通道上面
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0B,MOTOR_DIRECTION_PIN);

  //配置mcpwm信息
  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);//初始化mcpwm的某一个单元并绑定时钟
}

void advance(/*范围: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);//给MOTOR_STEP_PIN一个持续的高电平

/**
 * @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);//MOTOR_DIRECTION_PIN引脚输出占空比为“speed”的PWM波
}

void retreat(/*范围:0~100*/uint8_t speed)
{
  //给MOTOR_STEP_PIN一个持续的低电平
  mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B);

  //MOTOR_DIRECTION_PIN引脚输出占空比为“speed”的PWM波
  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);
}

6.1.2 驱动带编码器直流电机

通过PID控制电机转动速度

/**
 *@brief motorSpeeddetectionbyPH_ENwithencoder.ino
 *@ 在PWM模式下的电机驱动程序(带编码器)
 */
#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;//用于提供给电机PWM功率值。
double Setpoint;
double Kp=0.6, Ki=5, Kd=0;
PID myPID(&abs_duration, &val_output, &Setpoint, Kp, Ki, Kd, DIRECT);

//初始化需要产生PWM信号的引脚
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);//绑定需要输出PWM的引脚到PWM通道上面
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0B,MOTOR_DIRECTION_PIN);

  //配置mcpwm信息
  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);//初始化mcpwm的某一个单元并绑定时钟
}

void advance(/*范围: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);//给MOTOR_STEP_PIN一个持续的高电平

/**
 * @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);//MOTOR_DIRECTION_PIN引脚输出占空比为“speed”的PWM波
}

void retreat(/*范围:0~100*/uint8_t speed)
{
  //给MOTOR_STEP_PIN一个持续的低电平
  mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B);

  //MOTOR_DIRECTION_PIN引脚输出占空比为“speed”的PWM波
  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;  //设置PID的输出值
  myPID.SetMode(AUTOMATIC);//设置PID为自动模式
  myPID.SetSampleTime(100);//设置PID采样频率为100ms
  EncoderInit();//Initialize the module
}

void loop() {
  abs_duration=abs(duration);
  result=myPID.Compute();//PID转换完成返回值为1
  if(result)
  {
    Serial.print("Pluse: ");
    Serial.println(duration);
    duration = 0; //计数清零等待下次计数
  }  
}

6.2 PWM模式驱动电机

PWM控制模式真值表

IN1 IN2 OUT1 OUT2 说明
0 0 Hi-Z Hi-Z 滑行(H 桥高阻抗)
0 1 L H 后退 (OUT2 → OUT1)
1 0 H L 前进 (OUT1 → OUT2)
1 1 L L 制动(低侧慢速衰减)

6.2.1 驱动直流电机

/**
 *@brief motorSpeeddetectionbyPWM.ino
 *@ 在PWM模式下的电机驱动程序
 */
#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

//初始化需要产生PWM信号的引脚
void mcpwm_init(void)
{
  //绑定需要输出PWM的引脚到PWM通道上面
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0A,MOTOR_PWM_IN1);
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0B,MOTOR_PWM_IN2);

  //配置mcpwm信息
  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*/;

  //初始化mcpwm的某一个单元并绑定时钟
  mcpwm_init(MCPWM_UNIT_0,MCPWM_TIMER_0,&pwm_config);
}

void advance(/*范围: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(/*范围:0~100*/uint8_t speed)
{
  //给MOTOR_DIRECTION_PIN一个持续的低电平
  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);
  
  //MOTOR_STEP_PIN引脚输出占空比为“speed”的PWM波
  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);
}

6.2.2 驱动带编码器直流电机

通过PID控制电机转动速度

/**
 *@brief motorSpeeddetectionbyPWMwithencoder.ino
 *@ 在PWM模式下的电机驱动程序(带编码器)
 */
#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;//用于提供给电机PWM功率值。
double Setpoint;
double Kp=0.6, Ki=5, Kd=0;
PID myPID(&abs_duration, &val_output, &Setpoint, Kp, Ki, Kd, DIRECT);

//初始化需要产生PWM信号的引脚
void mcpwm_init(void)
{
  //绑定需要输出PWM的引脚到PWM通道上面
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0A,MOTOR_PWM_IN1);
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0B,MOTOR_PWM_IN2);

  //配置mcpwm信息
  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*/;

  //初始化mcpwm的某一个单元并绑定时钟
  mcpwm_init(MCPWM_UNIT_0,MCPWM_TIMER_0,&pwm_config);
}


void advance(/*范围: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(/*范围:0~100*/uint8_t speed)
{
  //给MOTOR_DIRECTION_PIN一个持续的低电平
  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);
  
  //MOTOR_STEP_PIN引脚输出占空比为“speed”的PWM波
  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;  //设置PID的输出值
  myPID.SetMode(AUTOMATIC);//设置PID为自动模式
  myPID.SetSampleTime(100);//设置PID采样频率为100ms
  EncoderInit();//Initialize the module
}

void loop() {
  abs_duration=abs(duration);
  result=myPID.Compute();//PID转换完成返回值为1
  if(result)
  {
    Serial.print("Pluse: ");
    Serial.println(duration);
    duration = 0; //计数清零等待下次计数
  }  
}

6.3 驱动小车实践

按照接线图连接硬件,烧录代码,连接"ESP32 S3 Romeo",在浏览器进入192.168.4.1即可驱动小车和查看摄像头数据

使用前请下载安装

#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);//给PH一个持续的高电平
      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);//EN引脚输出占空比为“speed”的PWM波
      break;
  
    case 2:
      mcpwm_set_signal_high(MCPWM_UNIT_0,MCPWM_TIMER_1,MCPWM_GEN_B);//给PH一个持续的高电平
      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);//EN引脚输出占空比为“speed”的PWM波
      break;
  
    case 3:
      mcpwm_set_signal_high(MCPWM_UNIT_1,MCPWM_TIMER_0,MCPWM_GEN_B);//给PH一个持续的高电平
      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);//EN引脚输出占空比为“speed”的PWM波
      break;
  
    case 4:
      mcpwm_set_signal_high(MCPWM_UNIT_1,MCPWM_TIMER_1,MCPWM_GEN_B);//给PH一个持续的高电平
      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);//EN引脚输出占空比为“speed”的PWM波
      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);//给PH一个持续的低电平
      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);//EN引脚输出占空比为“speed”的PWM波
      break;
  
    case 2:
      mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_1,MCPWM_GEN_B);//给PH一个持续的低电平
      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);//EN引脚输出占空比为“speed”的PWM波
      break;
  
    case 3:
      mcpwm_set_signal_low(MCPWM_UNIT_1,MCPWM_TIMER_0,MCPWM_GEN_B);//给PH一个持续的低电平
      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);//EN引脚输出占空比为“speed”的PWM波
      break;
  
    case 4:
      mcpwm_set_signal_low(MCPWM_UNIT_1,MCPWM_TIMER_1,MCPWM_GEN_B);//给PH一个持续的低电平
      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);//EN引脚输出占空比为“speed”的PWM波
      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 );
}

//初始化需要产生PWM信号的引脚
void mcpwm_init(void)
{
  //配置mcpwm信息
  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速度  B方向
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0A,M1_EN);//电机1 GPIO
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0B,M1_PN);
  mcpwm_init(MCPWM_UNIT_0,MCPWM_TIMER_0,&pwm_config);//初始化mcpwm的某一个单元并绑定时钟
  
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM1A,M2_EN);//电机2 GPIO
  mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM1B,M2_PN);
  mcpwm_init(MCPWM_UNIT_0,MCPWM_TIMER_1,&pwm_config);//初始化mcpwm的某一个单元并绑定时钟
  
  mcpwm_gpio_init(MCPWM_UNIT_1,MCPWM0A,M3_EN);//电机3 GPIO
  mcpwm_gpio_init(MCPWM_UNIT_1,MCPWM0B,M3_PN);
  mcpwm_init(MCPWM_UNIT_1,MCPWM_TIMER_0,&pwm_config);//初始化mcpwm的某一个单元并绑定时钟
  
  mcpwm_gpio_init(MCPWM_UNIT_1,MCPWM1A,M4_EN);//电机4 GPIO
  mcpwm_gpio_init(MCPWM_UNIT_1,MCPWM1B,M4_PN);
  mcpwm_init(MCPWM_UNIT_1,MCPWM_TIMER_1,&pwm_config);//初始化mcpwm的某一个单元并绑定时钟
}


void setup(void) 
{
  Serial.begin(115200);
  while(axp.begin() != 0){
    Serial.println("init error");
    delay(1000);
  }
  axp.enableCameraPower(axp.eOV2640);//设置摄像头供电
  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());
}

常见问题

原因

  • 如果Loop中延时过短或者不加延时会导致烧录超时

  • 错误的调用一些函数会导致计算机不能识别USB

解决办法

  • 按住BOOT,再按下RST,然后松开两个按键,再烧录。

串口无打印

解决办法

  • 检查USB CDC是否处于Enable状态
  • 使用其他的串口调试助手查看打印信息

更多问题及有趣的应用,可以 访问论坛 进行查阅或发帖。

更多