回到首页 返回首页
回到顶部 回到顶部
返回上一页 返回上一页

Beetle 树莓派RP2350 - 使用PWM调速控制L298N 简单

头像 Xia-FPV 2025.05.25 21 0

Beetle 树莓派RP2350 - 使用PWM调速控制L298N

 

文章介绍了如何使用 DFRobot Beetle RP2350 开发板使用PWM控制L298N驱动模块对电动机进行调速。

 

感谢“无垠的广袤”大佬开源的拓展版

项目使用的扩展板详见: https://oshwhub.com/lijinlei0907/beetle-rp2350-expansion-board

 

 

模块介绍

 

L298N模块

模块逻辑.png

模块使用L298N作为主要驱动芯片,具有驱动能力强,发热量低,抗干扰能力强等特点。

 

主控芯片:L298N
工作模式:H桥驱动(双路)
逻辑电压:5V-7V
逻辑电流:0-36mA
驱动电压: 5-35V,如需要板内取电,则供电范围7V-35V
驱动电流:2A(MAX单桥)
存储温度:-20℃到+135℃
最大功率:25W
控制信号输入电压范围:低电平:- 0.3V≤Vin≤1.5V
高电平: 2.3V≤VinsVss
使能信号输入电压范围电平:-0.3≤Vins≤1.5(控制信号无效)

高电平: 2.3V≤VinsVss(控制信号有效)

模块逻辑.png

硬件连接

 

电机使能

GP0 ---- IN1(左电机使能)

GP1 ---- IN2(左电机使能)

GP26 ---- ENA(左电机PWM)

 

GP8 ---- IN3(右电机使能)

GP9 ---- IN4(右电机使能)

GP27 ---- ENB(右电机PWM)

 

PWM控制输入

GP16 ---- (左电机PWM输入)

GP18 ---- (右电机PWM输入)

 

OLED屏幕

GP5 ---- SCL

GP4 ---- SDA

 

实物连接

连接.jpg

 

L298N控制逻辑

逻辑.png
分割线.png

代码

 

/

RP2040双电机控制系统(带OLED显示)

功能:

1. 读取两个PWM信号控制左右电机

2. 信号丢失时自动停止电机

3. LED状态指示:

常亮:信号正常

快闪:信号丢失

4. 0.96寸OLED实时显示系统状态

硬件配置:

OLED: SCL=GP5, SDA=GP4 (I2C0)

电机控制:GP0,1,8,9,26,27

PWM输入:GP16(左), GP18(右)

状态LED:GP25

 /

 

#include

#include

#include


 

// ================= OLED配置 =================

#define SCREEN_WIDTH 128

#define SCREEN_HEIGHT 64

#define OLED_SDA 4      // GP4IN

#define OLED_SCL 5      // GP5

#define OLED_ADDR 0x3C  // I2C地址


 

Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, -1);


 

// ================= 电机控制引脚 =================

#define IN1 0     // 左电机方向1

#define IN2 1     // 左电机方向2

#define ENA 26    // 左电机PWM

#define IN3 8     // 右电机方向1

#define IN4 9     // 右电机方向2

#define ENB 27    // 右电机PWM


 

// ================= 遥控器输入 =================

#define PWM_LEFT 16    // 左摇杆信号

#define PWM_RIGHT 18   // 右摇杆信号


 

// ================= 状态指示 =================

#define LED_BUILTIN 25 // 板载LED


 

// ================= 全局变量 =================

// 信号检测

#define SIGNAL_TIMEOUT 100000  // 100ms超时(us)

unsigned long lastSignalTime = 0;

bool signalLost = false;


 

// 电机控制

int speedLeft = 0;

int speedRight = 0;


 

// LED控制

unsigned long previousLEDMillis = 0;

bool ledState = LOW;


 

// OLED控制

unsigned long lastDisplayUpdate = 0;

const int DISPLAY_INTERVAL = 200; // 刷新间隔(ms)


 

// ================= 初始化函数 =================

void setup() {

  // 初始化串口

  Serial.begin(115200);

  Serial.println("RP2040电机控制系统启动...");


 

  // 初始化I2C(RP2040专用方式)

  Wire.setSDA(OLED_SDA);

  Wire.setSCL(OLED_SCL);

  Wire.begin();

  Wire.setClock(400000); // 400kHz高速模式

 

  // 初始化OLED

  if(!display.begin(SSD1306_SWITCHCAPVCC, OLED_ADDR)) {

    Serial.println("OLED初始化失败!");

    while(true); // 卡死

  }

  display.clearDisplay();

  display.setTextSize(1);

  display.setTextColor(SSD1306_WHITE);

  display.setCursor(0,0);

  display.println("RP2350,Robt");

  display.println("OK,OK");

  display.display();

  delay(3000);


 

  // 初始化电机引脚

  pinMode(IN1, OUTPUT);

  pinMode(IN2, OUTPUT);

  pinMode(ENA, OUTPUT);

  pinMode(IN3, OUTPUT);

  pinMode(IN4, OUTPUT);

  pinMode(ENB, OUTPUT);


 

  // 初始化PWM输入

  pinMode(PWM_LEFT, INPUT);

  pinMode(PWM_RIGHT, INPUT);


 

  // 初始化LED

  pinMode(LED_BUILTIN, OUTPUT);

  digitalWrite(LED_BUILTIN, LOW);


 

  // 记录启动时间

  lastSignalTime = micros();

}


 

// ================= 紧急停止函数 =================

void emergencyStop() {

  digitalWrite(IN1, LOW);

  digitalWrite(IN2, LOW);

  analogWrite(ENA, 0);

  digitalWrite(IN3, LOW);

  digitalWrite(IN4, LOW);

  analogWrite(ENB, 0);

 

  // OLED显示紧急状态

  display.clearDisplay();

  display.setCursor(0,0);

  display.println("Jin,Ji");

  display.println("Deng,Dai-PWM...");

  display.display();

 

  Serial.println("急停!");

  delay(3000);

}


 

// ================= LED状态更新 =================

void updateLED() {

  if(signalLost) {

    if(millis() - previousLEDMillis >= 200) {

      previousLEDMillis = millis();

      ledState = !ledState;

      digitalWrite(LED_BUILTIN, ledState);

    }

  } else {

    digitalWrite(LED_BUILTIN, HIGH);

  }

}


 

// ================= OLED显示更新 =================

void updateDisplay() {

  if(millis() - lastDisplayUpdate < DISPLAY_INTERVAL) return;

  lastDisplayUpdate = millis();


 

  display.clearDisplay();

 

  // 1. 标题栏

  display.setTextSize(1);

  display.setCursor(0,0);

  display.print("RP2350");

  display.drawFastHLine(0, 10, display.width(), SSD1306_WHITE);


 

  // 2. 电机状态(紧凑布局)

  display.setCursor(0,15);

  display.print("L:");

  display.print(speedLeft);

  display.print(" R:");

  display.print(speedRight);

 

  // 3. 方向指示

  display.setCursor(0,25);

  display.print("Dir:");

  if(speedLeft > 0) display.print("Fwd");

  else if(speedLeft < 0) display.print("Rev");

  else display.print("Stop");

 

  // 4. 信号状态

  display.setCursor(0,40);

  display.print("Signal:");

  if(signalLost) {

    display.setTextColor(SSD1306_BLACK, SSD1306_WHITE);

    display.print("NO-PWM!");

    display.setTextColor(SSD1306_WHITE);

  } else {

    display.print("OK");

   

  }


 

  // 5. 运行时间

  display.setCursor(0,55);

  display.print("Up:");

  display.print(millis()/1000);

  display.print("s");


 

  display.display();

  //6.延时

  //delay(1000);

 


 

}


 

// ================= 主循环 =================

void loop() {

  // 1. 读取PWM信号

  unsigned long pwmLeft = pulseIn(PWM_LEFT, HIGH, SIGNAL_TIMEOUT);

  unsigned long pwmRight = pulseIn(PWM_RIGHT, HIGH, SIGNAL_TIMEOUT);


 

  // 2. 检测信号状态

  signalLost = (pwmLeft == 0 || pwmRight == 0);


 

  if(!signalLost) {

    lastSignalTime = micros();

   

    // 3. 计算电机速度

    speedLeft = constrain(map(pwmLeft, 1000, 2000, -255, 255), -255, 255);

    speedRight = constrain(map(pwmRight, 1000, 2000, -255, 255), -255, 255);


 

    // 4. 控制左电机

    if(speedLeft > 0) {

      digitalWrite(IN1, HIGH);

      digitalWrite(IN2, LOW);

      analogWrite(ENA, speedLeft);

    } else if(speedLeft < 0) {

      digitalWrite(IN1, LOW);

      digitalWrite(IN2, HIGH);

      analogWrite(ENA, -speedLeft);

    } else {

      digitalWrite(IN1, LOW);

      digitalWrite(IN2, LOW);

      analogWrite(ENA, 0);

    }


 

    // 5. 控制右电机

    if(speedRight > 0) {

      digitalWrite(IN3, HIGH);

      digitalWrite(IN4, LOW);

      analogWrite(ENB, speedRight);

    } else if(speedRight < 0) {

      digitalWrite(IN3, LOW);

      digitalWrite(IN4, HIGH);

      analogWrite(ENB, -speedRight);

    } else {

      digitalWrite(IN3, LOW);

      digitalWrite(IN4, LOW);

      analogWrite(ENB, 0);

    }

  } else {

    // 6. 信号丢失处理

    if(micros() - lastSignalTime > 200000) {

      emergencyStop();

    }

  }


 

  // 7. 更新状态指示

  updateLED();

  updateDisplay();


 

  // 8. 调试输出

  Serial.print("L:");

  Serial.print(pwmLeft);

  Serial.print(" R:");

  Serial.print(pwmRight);

  Serial.print(" | ");

  Serial.println(signalLost ? "信号丢失" : "信号正常");


 

  delay(20);

分割线.png

效果展示

 

Beetle 树莓派RP2350 - 使用PWM调速控制L298N_哔哩哔哩_bilibili

评论

user-avatar