在使用灰度传感器制作巡迹小车时,传统循迹方法通常采用三灰度循迹,即在小车车体的左中右三个位置分别放置三个灰度传感器,根据传感器是否触发或是传感器返回的数值大小来判断车体的三种位置状态:中正、偏左、偏右,但是这样的循迹方式有一个很大的缺点,当车体发生一次歪斜之后,继续巡线过程中车体左右摇摆严重,非常影响小车前进速度以及前进方向的稳定。
本文提出一种双灰度传感器巡黑线的方案,经过实际验证,该方案很好的解决了上述问题。
注意: 在下面的图中,棕色的方形块和四个蓝色的圆柱表示一个小车的车体,眼睛表示灰度传感器,黑色的半透明阴影表示黑色的循迹线。
图1.直行状态(从底部向上看)
图2.左偏状态(从底部向上看)
通常情况下,当车体歪斜一个不小的角度时,小车右边的传感器才能检测到黑色,然后执行右转的代码,使车体回正,如下图所示;
图3.执行回正代码后小车状态(从底部向上看)
在回正的过程中,代码逻辑是要小车转向直到中间传感器检测到黑色,完成转向后,小车的状态通常是这样;此时中间传感器检测到黑线,判断为中正,保持直行,但是这样走一小段距离,小车左边传感器就检测到了黑线,又要往左转向,然后车体再次歪斜,再往右转向;如此周而复始,就造成了小车循迹过程中左右摇摆的现象。
图4.传统循迹方法下的小车轨迹
为解决上述问题,我想了很多种方案,比如:
注意: 在下面的图中,棕色的方形块和四个蓝色的圆柱表示一个小车的车体,两个眼睛表示两个灰度传感器,黑色的半透明阴影表示黑色的线。
2019.11.23 完善
注: 这里其实只提出了一个思路,因为是软硬件结合的,不同的硬件结构的代码也完全不一样,在实际操作的时候还是会遇到很多问题;
比如这种循迹方法只能巡直线和弯度不大的转弯,如果要过直角弯还需要增加两个灰度传感器进行辅助判断;
反正,就是具体问题具体解决嘛。。。
这里给出我的代码,仅供参考:) 希望能帮到你~
#include
int sensor_pin[4] = {A0,A4,A2,A3};
int sensor_value[4] = {0,0,0,0};
const int LEFT = 0;//normal left
const int RIGHT = 1;//normal right
const int LEFT_RightAngle = 2;//right angle left
const int RIGHT_RightAngle = 3;//right angle right
const int STRAIGHT = 4;
const int BlackLimit_ML = 680;
const int BlackLimit_MR = 550;
const int BlackLimit_L = 500;
const int BlackLimit_R = 500;
const int HIGH_RIGHT = 234;
Servo myservo;
boolean isobstacle = 0;
void setup(){
pinMode(5,OUTPUT);//motor out
pinMode(6,OUTPUT);
pinMode(9,OUTPUT);//motor out
pinMode(10,OUTPUT);
pinMode(8,INPUT);//touch sensor
myservo.attach(11);
Serial.begin(9600);
}
//judge whether an obstacle in front of us,return true when it is
boolean is_obstacle(){
isobstacle = digitalRead(8);
return isobstacle;
}
//read sensor value
void read_value(){
for(int i = 0;i < 4;i++){
sensor_value[i] = analogRead(sensor_pin[i]);
}
}
//turn to a direction
void turn(const int direction_){
switch(direction_){
case LEFT:
analogWrite(5,LOW);
digitalWrite(6,HIGH_RIGHT);//right wheel
digitalWrite(9,LOW);
digitalWrite(10,LOW);//left wheel
while(sensor_value[2] > BlackLimit_MR){//sensor_value[1] > BlackLimit_M
read_value();
delay(5);
}
break;
case RIGHT:
digitalWrite(5,LOW);
analogWrite(6,LOW);//right wheel
digitalWrite(9,LOW);
digitalWrite(10,HIGH);//left wheel
while(sensor_value[1] > BlackLimit_ML){//sensor_value[1] > BlackLimit_M
read_value();
delay(5);
}
break;
case LEFT_RightAngle:
digitalWrite(5,LOW);
analogWrite(6,HIGH_RIGHT);//right wheel
digitalWrite(9,HIGH);
digitalWrite(10,LOW);//left wheel
while(sensor_value[1] > BlackLimit_ML){//sensor_value[1] > BlackLimit_M
read_value();
if(sensor_value[3] < BlackLimit_R)
break;
delay(5);
}
break;
case RIGHT_RightAngle:
digitalWrite(5,HIGH_RIGHT);
analogWrite(6,LOW);//right wheel
digitalWrite(9,LOW);
digitalWrite(10,HIGH);//left wheel
while(sensor_value[2] > BlackLimit_MR){//sensor_value[1] > BlackLimit_M
read_value();
if(sensor_value[0] < BlackLimit_L)
break;
delay(5);
}
break;
case STRAIGHT:
digitalWrite(5,LOW);
analogWrite(6,HIGH_RIGHT);//right wheel
digitalWrite(9,LOW);
digitalWrite(10,HIGH);//left wheel
break;
default:
digitalWrite(5,LOW);
analogWrite(6,HIGH_RIGHT);//right wheel
digitalWrite(9,LOW);
digitalWrite(10,HIGH);//left wheel
break;
}
}
//judge what direction to turn with sensor value
void judge_turn(){
read_value();
if(sensor_value[0] < BlackLimit_L && sensor_value[3] > BlackLimit_R){//turn left right tangle
Serial.println(LEFT_RightAngle);
turn(LEFT_RightAngle);
}
else if(sensor_value[0] > BlackLimit_L && sensor_value[3] < BlackLimit_R){//turn right right tangle
Serial.println(RIGHT_RightAngle);
turn(RIGHT_RightAngle);
}
else if(sensor_value[1] > BlackLimit_ML && sensor_value[2] < BlackLimit_MR){
Serial.println(RIGHT);
turn(RIGHT);
}
else if(sensor_value[1] < BlackLimit_ML && sensor_value[2] > BlackLimit_MR){
Serial.println(LEFT);
turn(LEFT);
}
else{
Serial.println(STRAIGHT);
turn(STRAIGHT);
}
}
void run(){
judge_turn();
delay(10);
}
void loop(){
run();
}