本系列教程讲解零知小车套件以零知esp32为主控,使用零知开源平台进行智能小车开发。
实现的功能:红外循迹、超声避障、直线运行、手机蓝牙控制等基本功能。
扩展:可以在小车上加入其它传感器模块进行扩展,比如加入摄像头模块进行监控、加入火焰传感器做灭火小车、加入更多超声波模块实现自动跟随...
零知两轮小车入门版(ESP32主控)教程1-小车组装
零知两轮小车入门版(ESP32主控)教程2-让小车跑起来
零知两轮小车入门版(ESP32主控)教程3-手机WiFi/蓝牙控制小车
零知两轮小车入门版(ESP32主控)教程4-超声波自动避障
零知两轮小车入门版(ESP32主控)教程5-红外循迹
零知两轮小车入门版(ESP32主控)教程6-使用PID走直线
(1)组装好的智能小车
(2)零知ESP32
循迹小车是利用小车前面的红外循迹模块感应地面上的白色线条来控制小车左右轮子的速度进行转弯的,实现代码如下所示
/**********************************************************
* 文件: xunji.ino by 零知实验室([url=http://www.lingzhilab.com]www.lingzhilab.com[/url])
* -^^- 零知开源,让电子制作变得更简单! -^^-
* 时间: 2019/12/02 14:56
* 说明:
************************************************************/
//设置电机引脚
#define LEFT_MOTO1 32
#define LEFT_MOTO2 33
#define RIGHT_MOTO1 25
#define RIGHT_MOTO2 26
//#define LEFT_MOTO1 27
//#define LEFT_MOTO2 14
//#define RIGHT_MOTO1 12
//#define RIGHT_MOTO2 13
//寻迹模块引脚
#define XUNJI1 17
#define XUNJI2 16
#define XUNJI3 4
#define XUNJI4 2
#define XUNJI5 15
//循迹转弯调整
#define Speed 160
#define TraceLSpeed 180
#define TraceHSpeed 180
#define TraceSpeed 180
//循迹的颜色,非黑即白
#define BLACK 0
#define WHITE 1
//黑底白线,若白底黑线,请调换颜色
#define LINE WHITE
#define GROUND BLACK
// 复位或上电后运行一次:
void setup() {
//在这里加入初始化相关代码,只运行一次:
Serial.begin(9600);
pinMode(LEFT_MOTO1,OUTPUT);
pinMode(LEFT_MOTO2,OUTPUT);
pinMode(RIGHT_MOTO1,OUTPUT);
pinMode(RIGHT_MOTO2,OUTPUT);
pinMode(XUNJI1,INPUT);
pinMode(XUNJI2,INPUT);
pinMode(XUNJI3,INPUT);
pinMode(XUNJI4,INPUT);
pinMode(XUNJI5,INPUT);
ledcAttachPin(LEFT_MOTO1,1);
ledcAttachPin(LEFT_MOTO2,2);
ledcAttachPin(RIGHT_MOTO1,3);
ledcAttachPin(RIGHT_MOTO2,4);
ledcSetup(1, 12000, 8);
ledcSetup(2, 12000, 8);
ledcSetup(3, 12000, 8);
ledcSetup(4, 12000, 8);
}
//一直循环执行:
void loop() {
// 在这里加入主要程序代码,重复执行:
lineTrace(); //自动寻迹
}
//电机控制,正值前进,负值后退
void motoRun(int speedL,int speedR){
if(speedL>0){
ledcWrite(1,speedL);
ledcWrite(2,0);
}else{
ledcWrite(1,0);
ledcWrite(2,-speedL);
}
if(speedR>0){
ledcWrite(3,0);
ledcWrite(4,speedR);
}else{
ledcWrite(3,-speedR);
ledcWrite(4,0);
}
}
//停车
void motoStop(){
ledcWrite(1,255);
ledcWrite(2,255);
ledcWrite(3,255);
ledcWrite(4,255);
}
void lineTrace()
{
//读取红外寻迹模块的状态
int IR_1 = digitalRead(XUNJI1);
int IR_2 = digitalRead(XUNJI2);
int IR_3 = digitalRead(XUNJI3);
int IR_4 = digitalRead(XUNJI4);
int IR_5 = digitalRead(XUNJI5);
Serial.println("—————————————");
char c[256];
sprintf(c,"%d %d %d %d %d",IR_1,IR_2,IR_3,IR_4,IR_5);
Serial.println(c);
//五路不在白线上
if(IR_1 == GROUND && IR_2 == GROUND && IR_3 == GROUND && IR_4 == GROUND && IR_5 == GROUND)
{
motoRun(Speed,Speed);
Serial.println("直行。");
}
//五路循迹中心的在白线上
else if(IR_1 == GROUND && IR_2 == GROUND && IR_3 == LINE && IR_4 == GROUND && IR_5 == GROUND)
{
motoRun(Speed,Speed);
Serial.println("直行。。");
}
//五路循迹 2,3,4 在白线上
else if(IR_1 == GROUND && IR_2 == LINE && IR_3 == LINE && IR_4 == LINE && IR_5 == GROUND)
{
motoRun(Speed,Speed);
Serial.println("直行。");
}
//五路循迹 1 左侧边缘在白线上
else if((IR_1 == LINE && IR_2 == GROUND && IR_3 == GROUND && IR_4 == GROUND && IR_5 == GROUND)
||(IR_1==LINE &&IR_2 == LINE &&IR_3 == GROUND &&IR_4 == GROUND && IR_5 == GROUND)
||(IR_1==LINE &&IR_2 == LINE &&IR_3 == LINE &&IR_4 == GROUND && IR_5 == GROUND))
{
motoRun(-180,240);
Serial.println("左大转..直角");
}
//五路循迹 5 右侧边缘在白线上
else if((IR_1 == GROUND && IR_2 == GROUND && IR_3 == GROUND && IR_4 == GROUND && IR_5 == LINE)
||(IR_1==GROUND &&IR_2 == GROUND &&IR_3 == GROUND &&IR_4 == LINE && IR_5 == LINE)
||(IR_1==GROUND &&IR_2 == GROUND &&IR_3 == LINE &&IR_4 == LINE && IR_5 == LINE))
{
motoRun(240,-175);
Serial.println("右大转。。直角");
}
//五路循迹 2,3 在白线上 直行左侧发生偏移:向左转调整
else if(IR_1 == GROUND && IR_2 == LINE && IR_3 == LINE && IR_4 == GROUND && IR_5 == GROUND)
{
// carGo(carRightSlow);
// motorRun(1,true,180);
// motorRun(2,true,255);
motoRun(0,160);
Serial.println("左偏移。");//用左边轮子
}
//五路循迹 3,4 在白线上 直行右侧发生偏移:向左转调整
else if(IR_1 == GROUND && IR_2 == GROUND && IR_3 == LINE && IR_4 == LINE && IR_5 == GROUND)
{
// carGo(carRightSlow);
// motorRun(1,true,255);
// motorRun(2,true,180);
motoRun(160,0);
Serial.println("右偏移。");//用左边轮子
}
//五路循迹 2 在白线上 向左小转
else if(IR_1 == GROUND && IR_2 == LINE && IR_3 == GROUND && IR_4 == GROUND && IR_5 == GROUND)
{
// carGo(carLeftSlow);
motoRun(0,160);
Serial.println("左小转");
}
//五路循迹 4 在白线上 向右小转
else if(IR_1 == GROUND && IR_2 == GROUND && IR_3 == GROUND && IR_4 == LINE && IR_5 == GROUND)
{
// carGo(carRightSlow);
motoRun(Speed,0);
Serial.println("右小转。。");
} else{
motoRun(160,160);
}
}
将以上代码验证上传至esp32,智能小车就可以自动循迹了