
PS2无线遥控器+L298N四路电机驱动+ESP32
小车程序一(只有向前、向后、停车,不可遥控)
from machine import Pin,PWM
import time
pin1=PWM(Pin(19),freq=1000) #左前 红1
pin2=PWM(Pin(18),freq=1000)
pin3=PWM(Pin( 5),freq=1000) #左后 红3
pin4=PWM(Pin(17),freq=1000)
pin5=PWM(Pin(16),freq=1000) #右前 黑5
pin6=PWM(Pin( 4),freq=1000)
pin7=PWM(Pin( 0),freq=1000) #右后 黑7
pin8=PWM(Pin( 2),freq=1000)
def car_forward():
pin1.duty(1000) #左前
pin2.duty(0)
pin3.duty(1000) #左后
pin4.duty(0)
pin5.duty(1000) #右前
pin6.duty(0)
pin7.duty(1000) #右后
pin8.duty(0)
def car_back():
pin1.duty(0) #左前
pin2.duty(1000)
pin3.duty(0) #左后
pin4.duty(1000)
pin5.duty(0) #右前
pin6.duty(1000)
pin7.duty(0) #右后
pin8.duty(1000)
def car_stop():
pin1.duty(0)
pin2.duty(0)
pin3.duty(0)
pin4.duty(0)
pin5.duty(0)
pin6.duty(0)
pin7.duty(0)
pin8.duty(0)
i=1
try:
while True:
print("运行次数:",i)
print("正转+++++")
car_forward()
time.sleep(2)
car_stop()
time.sleep(1)
print("倒转-----")
car_back()
time.sleep(2)
car_stop()
time.sleep(1)
i=i+1
except KeyboardInterrupt:
print('KeyboardInterrupt 程序被人为中止....')
finally:
pin1.deinit()
pin2.deinit()
pin3.deinit()
pin4.deinit()
pin5.deinit()
pin6.deinit()
pin7.deinit()
pin8.deinit()
print('Exit 程序共运行了'+str(i)+'次,程序结束。')
小车程序二(支持PS2遥控器,麦克纳姆轮,可左右平移、斜向移动等)
from machine import Pin,PWM
from ps3 import PS2Controller
import time
import os
# #############################################
# PS2 遥控器
# #############################################
ps2ctl = PS2Controller(di_pin_no=26, do_pin_no=27, cs_pin_no=14, clk_pin_no=12)
ps2ctl.init()
# #############################################
# 小车轮子控制
# #############################################
pin1=PWM(Pin(19),freq=1000) #左前 红1
pin2=PWM(Pin(18),freq=1000)
pin3=PWM(Pin( 5),freq=1000) #左后 红3
pin4=PWM(Pin(17),freq=1000)
pin5=PWM(Pin(16),freq=1000) #右前 黑5
pin6=PWM(Pin( 4),freq=1000)
pin7=PWM(Pin( 0),freq=1000) #右后 黑7
pin8=PWM(Pin( 2),freq=1000)
#前进
def car_forward(speed):
pin1.duty(speed) #左前
pin2.duty(0)
pin3.duty(speed) #左后
pin4.duty(0)
pin5.duty(speed) #右前
pin6.duty(0)
pin7.duty(speed) #右后
pin8.duty(0)
#后退、倒车、倒转
def car_back(speed):
pin1.duty(0) #左前
pin2.duty(speed)
pin3.duty(0) #左后
pin4.duty(speed)
pin5.duty(0) #右前
pin6.duty(speed)
pin7.duty(0) #右后
pin8.duty(speed)
# 普通左转 = 左前、左后后退, 右前、右后前进
def car_left(speed):
pin1.duty(0) #左前
pin2.duty(speed)
pin3.duty(0) #左后
pin4.duty(speed)
pin5.duty(speed) #右前
pin6.duty(0)
pin7.duty(speed) #右后
pin8.duty(0)
# 普通右转 = 左前、左后前进, 右前、右后后退
def car_right(speed):
pin1.duty(speed) #左前
pin2.duty(0)
pin3.duty(speed) #左后
pin4.duty(0)
pin5.duty(0) #右前
pin6.duty(speed)
pin7.duty(0) #右后
pin8.duty(speed)
#停车、停止
def car_stop():
pin1.duty(0)
pin2.duty(0)
pin3.duty(0)
pin4.duty(0)
pin5.duty(0)
pin6.duty(0)
pin7.duty(0)
pin8.duty(0)
# 左平移=左前倒转、左后前进、右前前进、右后倒转
def car_left_pingyi(speed):
pin1.duty(0) #左前
pin2.duty(speed)
pin3.duty(speed) #左后
pin4.duty(0)
pin5.duty(speed) #右前
pin6.duty(0)
pin7.duty(0) #右后
pin8.duty(speed)
# 右平移=左前前进、左后倒转、右前倒转、右后前进
def car_right_pingyi(speed):
pin1.duty(speed) #左前
pin2.duty(0)
pin3.duty(0) #左后
pin4.duty(speed)
pin5.duty(0) #右前
pin6.duty(speed)
pin7.duty(speed) #右后
pin8.duty(0)
# 左上角 = 左前不动、左后前进、右前前进、右后不动
def car_left_up(speed):
pin1.duty(0) #左前
pin2.duty(0)
pin3.duty(speed) #左后
pin4.duty(0)
pin5.duty(speed) #右前
pin6.duty(0)
pin7.duty(0) #右后
pin8.duty(0)
# 左下角 = 左前倒退、左后不动、右前不动、右后倒退
def car_left_down(speed):
pin1.duty(0) #左前
pin2.duty(speed)
pin3.duty(0) #左后
pin4.duty(0)
pin5.duty(0) #右前
pin6.duty(0)
pin7.duty(0) #右后
pin8.duty(speed)
# 右上角 = 左前前进、左后不动、右前不动、右后前进
def car_right_up(speed):
pin1.duty(speed) #左前
pin2.duty(0)
pin3.duty(0) #左后
pin4.duty(0)
pin5.duty(0) #右前
pin6.duty(0)
pin7.duty(speed) #右后
pin8.duty(0)
# 右下角 = 左前不动、左后倒退、右前倒退、右后不动
def car_right_down(speed):
pin1.duty(0) #左前
pin2.duty(0)
pin3.duty(0) #左后
pin4.duty(speed)
pin5.duty(0) #右前
pin6.duty(speed)
pin7.duty(0) #右后
pin8.duty(0)
# ##################################################
# 主循环开始!!!
# ##################################################
i=1 #循环次数
speed=400 #初始速度,最高1000. 低于400容易电压太低驱动不了
print("小车程序开始运行,正在等待PS2遥控器按键(按start停车)")
try:
while True:
key_car= ps2ctl.read_once() # 收到的字符格式为 keys:UP,RIGHT: pos(lx,ly):0,-1: pos(rx,ry): 0,-1:
#print("检测到按键:",key_car)
key_list= key_car.split(':') # 用:来将字符串进行分割,写入数组key_list中
# key_list[1] 输入的按键
# key_list[3] 左摇杆坐标
# key_list[5] 右摇杆坐标
# 停止 = 遥控器 start = 4
if key_list[1]=="START" :
print(key_car," 停止.......")
car_stop()
# 前进 = 遥控器 左摇杆 上 = 5
# 前进 = 遥控器 右摇杆 上 = 13
if key_list[1]=="UP" or key_list[1]=="TRIANGLE":
print(key_car," 前进")
car_forward(speed)
# 后退 = 遥控器 左摇杆 下 = 7
# 后退 = 遥控器 右摇杆 下 = 15
if key_list[1]=="DOWN" or key_list[1]=="CROSS":
print(key_car," 后退")
car_back(speed)
# 左平移 = 遥控器 左摇杆左 = 8
if key_list[1]=="LEFT":
print(key_car," 左平移")
car_left_pingyi(speed)
# 右平移 = 遥控器 左摇杆右 = 6
if key_list[1]=="RIGHT":
print(key_car," 右平移")
car_right_pingyi(speed)
# 左转 = 遥控器 右摇杆 左 = 16
if key_list[1]=="SQUARE" :
print(key_car," 左转")
car_left(speed)
# 右转 = 遥控器 右摇杆 右 = 14
if key_list[1]=="CIRCLE":
print(key_car," 右转")
car_right(speed)
# 左上方 = 遥控器 左L1 = 11
if key_list[1]=="UP,LEFT":
print(key_car," 左上方")
car_left_up(speed)
# 左下方 = 遥控器 左L2 = 9
if key_list[1]=="DOWN,LEFT":
print(key_car," 左下方")
car_left_down(speed)
# 右上方 = 遥控器 右R1 = 12
if key_list[1]=="UP,RIGHT":
print(key_car," 右上方")
car_right_up(speed)
# 右下方 = 遥控器 右R2 = 10
if key_list[1]=="RIGHT,DOWN":
print(key_car," 右下方")
car_right_down(speed)
# L1 加速
if key_list[1]=="L1" and speed<1000:
speed=speed+100
print("当前速度已经加速至:",speed)
# L2 减速
if key_list[1]=="L2" and speed>400:
speed=speed-100
print("当前速度已经降低至:",speed)
# 右侧 三角+X,同时按下,删除main.py 取消自动启动
if key_list[1]=="TRIANGLE,CROSS" :
os.remove("main.py")
print("----------- main.py 已经删除 ----------")
car_stop()
# SELECT = 1 L3 = 2 R3 = 3 START = 4
# UP = 5 RIGHT = 6 DOWN = 7 LEFT = 8
# L2 = 9 R2 = 10 L1 = 11 R1 = 12
# TRIANGLE = 13 CIRCLE = 14 CROSS = 15 SQUARE = 16
i=i+1
time.sleep(0.1)
except KeyboardInterrupt:
print('KeyboardInterrupt 程序被人为中止....')
finally:
pin1.deinit()
pin2.deinit()
pin3.deinit()
pin4.deinit()
pin5.deinit()
pin6.deinit()
pin7.deinit()
pin8.deinit()
print('Exit 程序共运行了'+str(i)+'次,程序结束。')
附:麦克纳姆轮行走转向原理
特别注意:四个麦克纳姆轮,车轮呈X型安装,每一个均需要单独控制,所以要使用四路的电机驱动板

麦克纳姆轮行走转向原理
网友评论