-
#include
-
-
// Pins
-
byte leftIRPin = A0;
-
byte rightIRPin = A1;
-
byte upIRPin = A2;
-
byte downIRPin = A3;
-
-
byte lrServoPin = 2;
-
byte udServoPin = 3;
-
-
byte motorPin1 = 4;
-
byte motorPin2 = 5;
-
byte motorPin3 = 6;
-
byte motorPin4 = 7;
-
-
byte irLEDPin = 8;
-
-
// Servos
-
Servo lrServo;
-
Servo udServo;
-
-
int lrServoPos = 1500;
-
int udServoPos = 1500;
-
-
//IR values
-
int leftValue_amb;
-
int rightValue_amb;
-
int upValue_amb;
-
int downValue_amb;
-
-
int leftValue;
-
int rightValue;
-
int upValue;
-
int downValue;
-
-
int distance; // from 0 – 1000, the larger the closer
-
int minDistance = 165;
-
int servoAdjust = 25;
-
int minDif = 30;
-
-
-
void ReadIR(){
-
-
digitalWrite(irLEDPin, HIGH);
-
delay(15);
-
-
// total values
-
leftValue = analogRead(leftIRPin);
-
rightValue = analogRead(rightIRPin);
-
upValue = analogRead(upIRPin);
-
downValue = analogRead(downIRPin);
-
-
digitalWrite(irLEDPin, LOW);
-
delay(15);
-
-
leftValue_amb = analogRead(leftIRPin);
-
rightValue_amb = analogRead(rightIRPin);
-
upValue_amb = analogRead(upIRPin);
-
downValue_amb = analogRead(downIRPin);
-
-
leftValue = leftValue – leftValue_amb;
-
rightValue = rightValue – rightValue_amb;
-
upValue = upValue – upValue_amb;
-
downValue = downValue – downValue_amb;
-
-
distance = (leftValue + rightValue + upValue +downValue)/4;
-
-
-
}
-
-
-
void setup()
-
{
-
-
pinMode(irLEDPin, OUTPUT);
-
pinMode(motorPin1, OUTPUT);
-
pinMode(motorPin2, OUTPUT);
-
pinMode(motorPin3, OUTPUT);
-
pinMode(motorPin4, OUTPUT);
-
-
lrServo.attach(lrServoPin);
-
udServo.attach(udServoPin);
-
lrServo.writeMicroseconds(lrServoPos);
-
udServo.writeMicroseconds(udServoPos);
-
-
}
-
-
-
void loop()
-
{
-
-
ReadIR();
-
-
// =============== Track Object =================
-
-
if (distance > minDistance){
-
if ((rightValue – leftValue) > minDif)
-
lrServoPos = lrServoPos – servoAdjust ;
-
else if ((leftValue – rightValue) > minDif)
-
lrServoPos = lrServoPos + servoAdjust ;
-
if ((upValue – downValue) > minDif)
-
udServoPos = udServoPos + servoAdjust ;
-
else if ((downValue – upValue) > minDif)
-
udServoPos = udServoPos – servoAdjust ;
-
}
-
/*
-
// =============== Track Object =================
-
int temp = leftValue – rightValue;
-
if (distance > 70){
-
if (rightValue > leftValue)
-
lrServoPos = lrServoPos – (rightValue – leftValue)/5 ;
-
else
-
lrServoPos = lrServoPos + (leftValue – rightValue)/5 ;
-
if (upValue > downValue)
-
udServoPos = udServoPos + (upValue – downValue)/5 ;
-
else
-
udServoPos = udServoPos – (downValue – upValue)/5 ;
-
}
-
*/
-
-
lrServoPos = constrain(lrServoPos,600,2300);
-
udServoPos = constrain(udServoPos,600,2300);
-
-
lrServo.writeMicroseconds(lrServoPos);
-
-
udServo.writeMicroseconds(udServoPos);
-
-
// =============== turn body =================
-
-
if (lrServoPos < 1100){
-
digitalWrite(motorPin1, LOW);
-
digitalWrite(motorPin2, HIGH);
-
digitalWrite(motorPin3, HIGH);
-
digitalWrite(motorPin4, LOW);
-
}
-
else if (lrServoPos > 1900){
-
digitalWrite(motorPin1, HIGH);
-
digitalWrite(motorPin2, LOW);
-
digitalWrite(motorPin3, LOW);
-
digitalWrite(motorPin4, HIGH);
-
}
-
-
else{
-
digitalWrite(motorPin1, LOW);
-
digitalWrite(motorPin2, LOW);
-
digitalWrite(motorPin3, LOW);
-
digitalWrite(motorPin4, LOW);
-
}
-
-
delay(10);
-
-