本系列教程讲解零知小车套件以零知迷你板为主控,使用零知开源平台进行智能小车开发。
使用的硬件:零知智能小车套件
实现的功能:红外循迹、超声避障、直线运行等基本功能。
扩展:可以在小车上加入其它传感器模块进行扩展,比如加入摄像头模块进行监控、加入火焰传感器做灭火小车、加入更多超声波模块实现自动跟随...
零知两轮小车入门版(零知mini主控)系列教程-小车组装
零知两轮小车入门版(零知mini主控)系列教程-程序控制电机开跑
零知两轮小车入门版(零知mini主控)系列教程-红外循迹走S弯
零知两轮小车入门版(零知mini主控)系列教程-超声波自动避障
零知两轮小车入门版(零知mini主控)系列教程-使用PID走直线
避障小车主要是通过小车前面的超声波模块来感应障碍物并测量距离,舵机调整方向,选择无障碍的一边通行,代码实现如下:
/**********************************************************
* 文件: lzsmartcar_v1.ino by 零知实验室([url]www.lingzhilab.com[/url])
* -^^- 零知开源,让电子制作变得更简单! -^^-
* 时间: 2019/11/20 15:50
* 说明: 零知智能小车-迷你板
************************************************************/
//调试信息
#define DEBUG_PRINT
#include <Servo.h>
Servo UltraServo;
/***************************************************************/
//引脚说明
//蓝牙模块
#define BTSerial Serial2
//电机模块
#define MotorIN1 2
#define MotorIN2 3
#define MotorIN3 4
#define MotorIN4 5
#define MotorIN5 8
#define MotorIN6 9
#define MotorIN7 10
#define MotorIN8 11
//循迹
#define TracePin1 18
#define TracePin2 17
//#define TracePin3 rst///
#define TracePin4 12
#define TracePin5 13
//舵机
#define ServoPWM1 15
#define ServoPWM2 16
#define ServoPWM3 21
#define ServoPWM4 24
//迷你传感器
#define MiniSensorWire Wire
//测速模块
#define SM1Pin 29
#define SM2Pin 28
//超声波
#define UltraTrigPin 31
#define UltraEchoPin 30
/***************************************************************/
//小车运行方向
enum carDirec{
carForward = 1,
carForwardSlow,
carBack,
carLeft,
carRight,
carForLeft,
carForRight,
carBacLeft,
carBacRight,
carRightFast,
carRightSlow,
carLeftFast,
carLeftSlow,
carStop
};
//循迹
#define MotorSpeedTrace 190
//#define MotorSpeedTraceSlow 220
#define MotorSpeedRoSlow 140
#define MotorSpeedRoFast 100
#define MotorSpeedSlow 140
//避障,转弯速度调节
#define MotorSpeedNormal 140 //正常前进速度
#define MotorSpeedRotate 240
#define MotorSpeedFast 80 //
void motorRun(byte motorNum, bool forward, int speed){
if(motorNum == 1){
if(forward){
analogWrite(MotorIN1,speed);
analogWrite(MotorIN2,255);
}else{
analogWrite(MotorIN1,255);
analogWrite(MotorIN2,speed);
}
}
if(motorNum == 2){
if(forward){
analogWrite(MotorIN3,speed);
analogWrite(MotorIN4,255);
}else{
analogWrite(MotorIN3,255);
analogWrite(MotorIN4,speed);
}
}
if(motorNum == 3){
if(forward){
analogWrite(MotorIN5,speed);
analogWrite(MotorIN6,255);
}else{
analogWrite(MotorIN5,255);
analogWrite(MotorIN6,speed);
}
}
if(motorNum == 4){
if(forward){
analogWrite(MotorIN7,255);
analogWrite(MotorIN8,speed);
}else{
analogWrite(MotorIN7,speed);
analogWrite(MotorIN8,255);
}
}
}
void motorStop()
{
analogWrite(MotorIN1,255);
analogWrite(MotorIN2,255);
analogWrite(MotorIN3,255);
analogWrite(MotorIN4,255);
analogWrite(MotorIN5,255);
analogWrite(MotorIN6,255);
analogWrite(MotorIN7,255);
analogWrite(MotorIN8,255);
}
//小车根据命令运行
void carGo(byte cmd){
switch(cmd){
case carForward:
motorRun(1,true,MotorSpeedNormal);
motorRun(2,true,MotorSpeedNormal);
motorRun(3,true,MotorSpeedNormal);
motorRun(4,true,MotorSpeedNormal);
break;
case carForwardSlow:
motorRun(1,true,MotorSpeedSlow);
motorRun(2,true,MotorSpeedSlow);
motorRun(3,true,MotorSpeedSlow);
motorRun(4,true,MotorSpeedSlow);
break;
case carBack:
motorRun(1,false,MotorSpeedNormal);
motorRun(2,false,MotorSpeedNormal);
motorRun(3,false,MotorSpeedNormal);
motorRun(4,false,MotorSpeedNormal);
break;
case carLeft:
motorRun(1,true,MotorSpeedRotate);
motorRun(2,true,MotorSpeedFast);
motorRun(3,true,MotorSpeedRotate);
motorRun(4,true,MotorSpeedFast);
break;
case carRight:
motorRun(1,true,MotorSpeedFast);
motorRun(2,true,MotorSpeedRotate);
motorRun(3,true,MotorSpeedFast);
motorRun(4,true,MotorSpeedRotate);
break;
case carForLeft:
motorRun(1,true,MotorSpeedRotate);
motorRun(2,true,MotorSpeedNormal);
motorRun(3,true,MotorSpeedRotate);
motorRun(4,true,MotorSpeedNormal);
break;
case carForRight:
motorRun(1,true,MotorSpeedNormal);
motorRun(2,true,MotorSpeedRotate);
motorRun(3,true,MotorSpeedNormal);
motorRun(4,true,MotorSpeedRotate);
break;
case carLeftFast:
motorRun(1,true,MotorSpeedRoFast);
motorRun(2,true,MotorSpeedTrace);
motorRun(3,true,MotorSpeedRoFast);
motorRun(4,true,MotorSpeedTrace);
break;
case carLeftSlow:
motorRun(1,true,MotorSpeedRoSlow);
motorRun(2,true,MotorSpeedTrace);
motorRun(3,true,MotorSpeedRoSlow);
motorRun(4,true,MotorSpeedTrace);
break;
case carRightFast:
motorRun(1,true,MotorSpeedTrace);
motorRun(2,true,MotorSpeedRoFast);
motorRun(3,true,MotorSpeedTrace);
motorRun(4,true,MotorSpeedRoFast);
break;
case carRightSlow:
motorRun(1,true,MotorSpeedTrace);
motorRun(2,true,MotorSpeedRoSlow);
motorRun(3,true,MotorSpeedTrace);
motorRun(4,true,MotorSpeedRoSlow);
break;
case carStop:
motorStop();
break;
default:
motorStop();
break;
}
}
//超声波测距
int getDistance()
{
digitalWrite(UltraTrigPin, LOW);
delayMicroseconds(2);
digitalWrite(UltraTrigPin, HIGH);
delayMicroseconds(10);
digitalWrite(UltraTrigPin, LOW);
int distance = pulseIn(UltraEchoPin, HIGH);
distance = distance/58.0;
return distance;
}
//超声波避障
void avoidance(int avoidDistance)
{
int i = 0;
int time = 30;//舵机速度
int disFor = 0;//探测的距离
int disLeft = 0;
int disRight = 0;
int d = 90;//障碍物范围
//首先探测正前方
UltraServo.write(d);
for(i=0;i<5;i++)
{
disFor += getDistance();
delay(50);
}
disFor = disFor/5;
#ifdef DEBUG_PRINT
Serial.print(" 前方距离:");
Serial.println(disFor);
#endif
if(disFor <= avoidDistance)//正前方有障碍物
{
//停车
carGo(carStop);
int t = 0;
int total = 0;
//探测右边
for(i=d; i>0;i--)
{
UltraServo.write(i);
delay(time);
}
for(i=0;i<5;i++)
{
disRight += getDistance();
delay(50);
}
disRight = disRight/5;
#ifdef DEBUG_PRINT
Serial.print(" 右侧距离:");
Serial.println(disRight);
#endif
UltraServo.write(d);
//探测左边
for(i=d; i<170;i++)
{
UltraServo.write(i);
delay(time);
}
for(i=0;i<5;i++)
{
disLeft += getDistance();
delay(50);
}
disLeft = disLeft/5;
#ifdef DEBUG_PRINT
Serial.print(" 左侧距离:");
Serial.println(disLeft);
#endif
UltraServo.write(d);
int rollTime = 380;
//两边都有障碍物,掉头
if((disLeft <= avoidDistance) && (disRight <= avoidDistance))
{
carGo(carBack);
Serial.println("--后退");
delay(rollTime*2);
}
else if(disLeft >= disRight)
{
carGo(carLeft);//左转
Serial.println("--左转");
delay(rollTime);
}
else if(disLeft < disRight)
{
carGo(carRight);//右转
Serial.println("--右转");
delay(rollTime);
}
carGo(carStop);//停止
}else{
carGo(carForward);//无障碍,前进
}
//delay(300);
}
// 复位或上电后运行一次:
void setup() {
//在这里加入初始化相关代码,只运行一次:
//串口调试
Serial.begin(9600);
//设置引脚
pinMode(MotorIN1,OUTPUT);
pinMode(MotorIN2,OUTPUT);
pinMode(MotorIN3,OUTPUT);
pinMode(MotorIN4,OUTPUT);
pinMode(MotorIN5,OUTPUT);
pinMode(MotorIN6,OUTPUT);
pinMode(MotorIN7,OUTPUT);
pinMode(MotorIN8,OUTPUT);
carGo(carStop);
//超声波
pinMode(UltraEchoPin,INPUT);
pinMode(UltraTrigPin,OUTPUT);
//超声波舵机
UltraServo.attach(ServoPWM1);
}
//一直循环执行:
void loop() {
avoidance(50);
}
将以上代码验证上传至智能小车的零知mini板上,小车就可以实现智能避障了。