Skip to content

Commit 3e55a3f

Browse files
committed
Create LineFollowing3m.ino
This was functional and now included Amarino reporting.
1 parent 50a572e commit 3e55a3f

File tree

1 file changed

+144
-0
lines changed

1 file changed

+144
-0
lines changed

LineFollowing3m.ino

+144
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,144 @@
1+
#include <Servo.h>
2+
#include <MeetAndroid.h>
3+
4+
Servo servoLeft;
5+
Servo servoRight;
6+
MeetAndroid meetAndroid;
7+
int onboardLed = 13;
8+
int i = 0;
9+
unsigned long time;
10+
unsigned long tinit = 0;
11+
12+
int sensorPin = 3;
13+
int sensorPin1 = 6;
14+
int sensorPin2 = 7;
15+
int qti[3];
16+
17+
int n = 0;
18+
int n1 = 0;
19+
int threshold = 20;
20+
21+
long result = 0;
22+
void setup()
23+
{
24+
Serial.begin(9600);
25+
Serial.println("start");
26+
meetAndroid.registerFunction(testEvent, 'A');
27+
meetAndroid.registerFunction(forward, 'b' );
28+
tone(4, 3000, 1000);
29+
pinMode(onboardLed, OUTPUT);
30+
digitalWrite(onboardLed, HIGH);
31+
servoLeft.attach(11);
32+
servoRight.attach(10);
33+
tinit = micros();
34+
}
35+
36+
//float threshold = RCtime(sensorPin)-((RCtime(sensorPin)+RCtime(sensorPin2))/2);
37+
//read & navigate function
38+
void loop()
39+
{
40+
meetAndroid.receive();
41+
//Serial.println(threshold);
42+
time = micros() - tinit;
43+
if (RCtime(sensorPin)>= threshold){
44+
qti[0] = 1;}
45+
else{
46+
qti[0]=0;}
47+
if (RCtime(sensorPin1)>= threshold){
48+
qti[1] = 1;}
49+
else{
50+
qti[1]=0;}
51+
if (RCtime(sensorPin2)>= threshold){
52+
qti[2] = 1;}
53+
else{
54+
qti[2]=0;}
55+
56+
n = random(-250,0);
57+
n1 = random(-250,0);
58+
if(qti[0]==0 && qti[1]==1 && qti[2]==0){
59+
servoLeft.writeMicroseconds(1700 + n);
60+
servoRight.writeMicroseconds(1300 - n1);
61+
}
62+
63+
else if(qti[0]==1 && qti[1]==1 && qti[2]==0){
64+
servoLeft.writeMicroseconds(1700 + n);
65+
servoRight.writeMicroseconds(1500);
66+
}
67+
68+
else if(qti[0]==1 && qti[1]==0 && qti[2]==0){
69+
servoLeft.writeMicroseconds(1700 + n);
70+
servoRight.writeMicroseconds(1700 + n1);
71+
}
72+
73+
else if(qti[0]==0 && qti[1]==1 && qti[2]==1){
74+
servoLeft.writeMicroseconds(1500 + n);
75+
servoRight.writeMicroseconds(1300 - n1);
76+
}
77+
78+
else if(qti[0]==0 && qti[1]==0 && qti[2]==1){
79+
servoLeft.writeMicroseconds(1300 - n);
80+
servoRight.writeMicroseconds(1300 - n1);
81+
}
82+
83+
else if(qti[0]==1 && qti[1]==1 && qti[2]==1){
84+
servoLeft.writeMicroseconds(1500);
85+
servoRight.writeMicroseconds(1500);
86+
i++;
87+
if(i>=5){
88+
meetAndroid.send("The Robot has Stopped:");
89+
meetAndroid.send(i);
90+
meetAndroid.send(time);
91+
}
92+
}
93+
delayMicroseconds(40);
94+
95+
//servoLeft.writeMicroseconds(1700);
96+
//servoRight.writeMicroseconds(1300);
97+
98+
//Serial.println(qti[0]);
99+
//Serial.println(qti[1]);
100+
//Serial.println(qti[2]);
101+
102+
}
103+
104+
105+
106+
long RCtime(int sensPin){
107+
long result = 0;
108+
pinMode(sensPin, OUTPUT);
109+
digitalWrite(sensPin, HIGH);
110+
delay(1);
111+
112+
pinMode(sensPin, INPUT);
113+
digitalWrite(sensPin, LOW);
114+
while(digitalRead(sensPin)){
115+
result++;
116+
}
117+
118+
return result;
119+
}
120+
121+
void testEvent(byte flag, byte numOfValues)
122+
{
123+
flushLed(300);
124+
flushLed(300);
125+
}
126+
127+
void flushLed(int time)
128+
{
129+
digitalWrite(onboardLed, LOW);
130+
delay(time);
131+
digitalWrite(onboardLed, HIGH);
132+
delay(time);
133+
}
134+
135+
void forward(byte flag, byte numOfValues)
136+
{
137+
servoLeft.writeMicroseconds(1700);
138+
servoRight.writeMicroseconds(1300);
139+
delay(100);
140+
tinit = micros();
141+
meetAndroid.send("The new initial time is:");
142+
meetAndroid.send(tinit);
143+
i = 0;
144+
}

0 commit comments

Comments
 (0)