零知两轮小车入门版(ESP32主控)教程4-超声波避障

本系列教程讲解零知小车套件以零知esp32为主控,使用零知开源平台进行智能小车开发。

使用的硬件:零知智能小车套件


实现的功能:红外循迹、超声避障、直线运行、手机蓝牙控制等基本功能。

扩展:可以在小车上加入其它传感器模块进行扩展,比如加入摄像头模块进行监控、加入火焰传感器做灭火小车、加入更多超声波模块实现自动跟随...


本系列教程目录

零知两轮小车入门版(ESP32主控)教程1-小车组装


零知两轮小车入门版(ESP32主控)教程2-让小车跑起来


零知两轮小车入门版(ESP32主控)教程3-手机WiFi/蓝牙控制小车


零知两轮小车入门版(ESP32主控)教程4-超声波自动避障


零知两轮小车入门版(ESP32主控)教程5-红外循迹


零知两轮小车入门版(ESP32主控)教程6-使用PID走直线

一、工具材料

(1)组装好的智能小车
(2)零知ESP32


二、程序代码

避障小车主要是通过小车前面的超声波模块来感应障碍物并测量距离,舵机调整方向,选择无障碍的一边通行,2WD代码实现如下:

							
							
	/**********************************************************
	*    文件: Avoidance_car.ino      by 零知实验室([url=http://www.lingzhilab.com]www.lingzhilab.com[/url])
	*    -^^- 零知开源,让电子制作变得更简单! -^^-
	*    时间: 2019/11/26 18:41
	*    说明: 避障小车
	************************************************************/
	 
	#include <Servo.h>
	//#include "analogWrite.h"
	 
	//设置电机引脚
	#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 SR04_TRIG 23
	#define SR04_ECHO 22
	 
	//舵机
	#define SERVO_PIN 21
	 
	Servo myServo;  //创建舵机实例
	 
	// 复位或上电后运行一次:
	void setup() {
	    //在这里加入初始化相关代码,只运行一次:
	        Serial.begin(9600);
	        pinBegin();
	        motoStop();
	         
	}
	 
	//一直循环执行:
	void loop() {
	    // 在这里加入主要程序代码,重复执行:
	        avoidance(40);  //开始避障,设置避障距离为40cm
	 
	}
	 
	void pinBegin(){
	        pinMode(LEFT_MOTO1,OUTPUT);
	        pinMode(LEFT_MOTO2,OUTPUT);
	        pinMode(RIGHT_MOTO1,OUTPUT);
	        pinMode(RIGHT_MOTO2,OUTPUT);
	 
	        //设置引脚输出PWM的通道        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);
	         
	        pinMode(SR04_ECHO,INPUT);
	        pinMode(SR04_TRIG,OUTPUT);
	 
	        myServo.attach(SERVO_PIN);
	}
	 
	//电机控制,正值前进,负值后退
	void motoRun(int speedL,int speedR){
	 
	        if(speedL>0){
	                ledcWrite(1,0);
	                ledcWrite(2,speedL);
	        }else{
	                ledcWrite(1,-speedL);
	                ledcWrite(2,0);
	        }
	        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);
	}
	 
	//超声波获取距离
	int getDistance()
	{
	        digitalWrite(SR04_TRIG, LOW);
	        delayMicroseconds(2);
	        digitalWrite(SR04_TRIG, HIGH);
	        delayMicroseconds(10);
	        digitalWrite(SR04_TRIG, LOW);
	         
	        int distance = pulseIn(SR04_ECHO, HIGH);
	        distance = distance/58.0;
	         
	        return distance;
	}
	 
	//避障
	void avoidance(int avoidDistance){
	        int i = 0;
	        int time = 15;
	        int delay_time = 10;
	 
	        //三个方向的距离
	        int disFor = 0;
	        int disLeft = 0;
	        int disRight = 0;
	 
	        int pos = 90;  //舵机初始角度
	        int rollTime = 380;  //转弯的时间,若转弯效果不理想,可调整
	         
	        myServo.write(pos);
	 
	        //获取5次距离求平均值
	        for(i=0;i<5;i++)
	        {
	                disFor += getDistance();
	                delay(delay_time);
	        }
	        disFor = disFor/5;
	        Serial.print("前方距离:");
	        Serial.println(disFor);
	         
	        if(disFor <= avoidDistance){  检测前方距离是否小于设定距离
	                motoStop();  //停车
	                 
	                //舵机向右侧移动
	                for(i=pos;i>0;i-=1)
	                {
	                        myServo.write(i);
	                        delay(time);
	                }
	                //测量右侧距离
	                for(i=0;i<5;i++)
	                {
	                        disRight += getDistance();
	                        delay(delay_time);
	                }
	                disRight = disRight/5;
	                 
	                Serial.print(" 右侧距离:");
	                Serial.println(disRight);
	                //舵机向左侧移动
	                for(i=0;i<180;i+=1)
	                {
	                        myServo.write(i);
	                        delay(time);
	                }
	                //测量左侧距离
	                for(i=0;i<5;i++)
	                {
	                        disLeft += getDistance();
	                        delay(delay_time);
	                }
	                disLeft = disLeft/5;
	                 
	                Serial.print(" 左侧距离:");
	                Serial.println(disLeft);
	                //舵机回正
	                for(i=180;i>pos;i-=1)
	                {
	                        myServo.write(i);
	                        delay(time);
	                }
	                 
	                if((disLeft <= avoidDistance) && (disRight <= avoidDistance))  //检测左右两边的距离是否都小于设定距离
	                {
	                        motoRun(240,-240);  //若效果不理想,可调整两轮速度或调整转弯时间
	                        Serial.println("掉头");
	                        delay(rollTime);
	                }
	                else if(disLeft >= disRight)
	                {
	                        motoRun(80,240);  //左转
	                        Serial.println("左转");
	                        delay(rollTime*1.5);
	                }
	                else if(disLeft < disRight)
	                {
	                        motoRun(240,80);  //右转
	                        Serial.println("右转");
	                        delay(rollTime*1.5);
	                }
	                motoStop();  //停车
	        }else{
	                motoRun(150,150);  //前行
	        }
	}