| 硬件:
1.3轮小车 1台 2.Arduino DM板 1个 3.GP2D12红外测距传感器 2个 4.杜邦线 若干 5.电机驱动板 1个 6.LCD1602 1个 7.7.2V电池包 1个
软件:
1.arduino-0011
实验目标:
使小车能自主地在房间内行驶,并自动躲避障碍物。
实验目的:
利用Arduino开发板与红外线测距传感器、电机驱动板、液晶显示等通讯,完成一些简单的任务,激发初学者对机器人的制作热情。
实验原理:
使用2个GP2D12成八字型安装,探测左右2边的障碍物,当然这样也会有个弊端,就是中间要是出现一个较小的障碍物就会探测不到,所以能安装3个GP2D12最好了。这里我们就用2个将就实验,实验原理很简单,就是左边探测到一定距离的障碍物就控制2个电机向右转,右边探测到一定距离的障碍物就控制2个电机向左转,至于小车转向多少度呢,这个小车没有使用编码盘和电子罗盘,所以转向就只用了个简单的延时来处理。
实验连线图:

实验实物图:


实验视频:
实验代码:
/********************************************************************/ int GP2D12_L=0; int GP2D12_R=1;
int ledpin = 13;
int LCD1602_RS=12;
int LCD1602_RW=11;
int LCD1602_EN=10;
int DB[] = {6, 7, 8, 9};
int en1 = 5; int in1 = 4; int in2 = 3; int en2 = 2; int in3 = 1; int in4 = 0;
char str1[]="www.DFRobot.cn";
char str2[]="L=00cm";
char str3[]="R=00cm";
/********************************************************************/
/********************************************************************/ void LCD_Command_Write(int command) { int i,temp; digitalWrite( LCD1602_RS,LOW); digitalWrite( LCD1602_RW,LOW); digitalWrite( LCD1602_EN,LOW);
temp=command & 0xf0; for (i=DB[0]; i <= 9; i++) { digitalWrite(i,temp & 0x80); temp <<= 1; } digitalWrite( LCD1602_EN,HIGH); delayMicroseconds(1); digitalWrite( LCD1602_EN,LOW);
temp=(command & 0x0f)<<4; for (i=DB[0]; i <= 10; i++) { digitalWrite(i,temp & 0x80); temp <<= 1; }
digitalWrite( LCD1602_EN,HIGH); delayMicroseconds(1); digitalWrite( LCD1602_EN,LOW); }
/********************************************************************/ void LCD_Data_Write(int dat) { int i=0,temp; digitalWrite( LCD1602_RS,HIGH); digitalWrite( LCD1602_RW,LOW); digitalWrite( LCD1602_EN,LOW);
temp=dat & 0xf0; for (i=DB[0]; i <= 9; i++) { digitalWrite(i,temp & 0x80); temp <<= 1; }
digitalWrite( LCD1602_EN,HIGH); delayMicroseconds(1); digitalWrite( LCD1602_EN,LOW);
temp=(dat & 0x0f)<<4; for (i=DB[0]; i <= 10; i++) { digitalWrite(i,temp & 0x80); temp <<= 1; }
digitalWrite( LCD1602_EN,HIGH); delayMicroseconds(1); digitalWrite( LCD1602_EN,LOW); }
/********************************************************************/ void LCD_SET_XY( int x, int y ) { int address; if (y ==0) address = 0x80 + x; else address = 0xC0 + x; LCD_Command_Write(address); }
/********************************************************************/ void LCD_Write_Char( int x,int y,int dat) { LCD_SET_XY( x, y ); LCD_Data_Write(dat); }
/********************************************************************/ void LCD_Write_String(int x,int y,char *s) { LCD_SET_XY( x, y ); //设置地址 while (*s) //写字符串 { LCD_Data_Write(*s); s ++; } }
/********************************************************************/ void Motor(char x,char y,char m,char n) { digitalWrite(en1,HIGH);//驱动1使能 digitalWrite(in1,x); digitalWrite(in2,y); digitalWrite(en2,HIGH);//驱动2使能 digitalWrite(in3,m); digitalWrite(in4,n); }
/********************************************************************/ void setup (void) { int i = 0; for (i=0; i <= 13; i++) { pinMode(i,OUTPUT); } LCD_Command_Write(0x01); delay(50); LCD_Command_Write(0x28);//4线 2行 2x7 delay(50); LCD_Command_Write(0x06); delay(50); LCD_Command_Write(0x0c); delay(50); LCD_Command_Write(0x80); }
/********************************************************************/ void loop (void) { float temp; int val_L,val_R; char i,a,b,c,d; LCD_Command_Write(0x02); delay(50); LCD_Write_String(1,0,str1); delay(50); LCD_Write_String(1,1,str2); delay(50); LCD_Write_String(9,1,str3); delay(50); while(1) { val_L = analogRead(GP2D12_L);//读左边GP2D12模拟信号 val_R = analogRead(GP2D12_R);//读右边GP2D12模拟信号 temp=val_L/5.8; val_L=90-temp;//90cm以上超出范围 temp=val_R/5.8; val_R=90-temp; LCD_Write_String(1,1,str2); LCD_Write_String(9,1,str3); a=0x30+val_L/10; b=0x30+val_L%10; c=0x30+val_R/10; d=0x30+val_R%10; LCD_Write_Char(3,1,a);//显示左右距离 LCD_Write_Char(4,1,b); LCD_Write_Char(11,1,c); LCD_Write_Char(12,1,d); if(val_L>30&&val_R>30)//30cm以内有障碍转向 { Motor(LOW,HIGH,LOW,HIGH); delay(500); } else if(val_R<30&&val_L<30) { Motor(HIGH,LOW,HIGH,LOW); delay(500); Motor(HIGH,LOW,LOW,HIGH); delay(500); } else if(val_L<30&&val_R>30) { Motor(HIGH,LOW,LOW,HIGH); delay(500); } else if(val_R<30&&val_L>30) { Motor(LOW,HIGH,HIGH,LOW); delay(500); } } }
|