-
Notifications
You must be signed in to change notification settings - Fork 9
/
Copy pathRobot1.ino
255 lines (230 loc) · 6.67 KB
/
Robot1.ino
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
/*
Robot version 1
ATtiny85, 2 motors, LED, two sensors
Sensor stuff:
both white : no prior : random walk
: prior : turn in direction of last black
one white : ideal situation, move straight
both black : no prior : random walk
: prior : turn in direction of last white
This code was written by Eric Heisler (shlonkin)
It is in the public domain, so do what you will with it.
*/
// Here are some parameters that you need to adjust for your setup
// Base speeds are the motor pwm values. Adjust them for desired motor speeds.
#define baseLeftSpeed 17
#define baseRightSpeed 17
// This determines sensitivity in detecting black and white
// measurment is considered white if it is > whiteValue*n/4
// where n is the value below. n should satisfy 0<n<4
// A reasonable value is 3. Fractions are acceptable.
#define leftSensitivity 3
#define rightSensitivity 3
// the pin definitions
#define lmotorpin 1 // PB1 pin 6
#define rmotorpin 0 // PB0 pin 5
#define lsensepin 3 //ADC3 pin 2
#define rsensepin 1 //ADC1 pin 7
#define ledpin 4 //PB4 pin 3
// some behavioral numbers
// these are milisecond values
#define steplength 300
#define smallturn 200
#define bigturn 500
#define memtime 1000
// variables
uint8_t lspd, rspd; // motor speeds
uint16_t lsenseval, rsenseval, lwhiteval, rwhiteval; // sensor values
// just for convenience and simplicity (HIGH is off)
#define ledoff PORTB |= 0b00010000
#define ledon PORTB &= 0b11101111
void setup(){
// setup pins
pinMode(lmotorpin, OUTPUT);
pinMode(rmotorpin, OUTPUT);
pinMode(2, INPUT); // these are the sensor pins, but the analog
pinMode(3, INPUT); // and digital functions use different numbers
ledoff;
pinMode(ledpin, OUTPUT);
analogWrite(lmotorpin, 0);
analogWrite(rmotorpin, 0);
lspd = baseLeftSpeed;
rspd = baseRightSpeed;
// give a few second pause to set the thing on a white surface
// the LED will flash during this time
lsenseval = 6;
while(lsenseval){
lsenseval--;
flashLED(1);
delay(989);
}
flashLED(4);
delay(500);
senseInit();
}
void loop(){
// followEdge() contains an infinite loop, so this loop really isn't necessary
followEdge();
}
void followEdge(){
// now look for an edge
uint8_t lastMove = 1; //0=straight, 1=left, 2=right
unsigned long moveEndTime = 0; // the millis at which to stop
unsigned long randomBits = micros(); // for a random walk
unsigned long prior = 0; // after edge encounter set to millis + memtime
uint8_t priorDir = 0; //0=left, 1=right, 2=both
uint8_t lastSense = 1; //0=edge, 1=both white, 2=both black
uint8_t i = 0; // iterator
while(true){
// only read sensors about once every 20ms
// it can be done faster, but this makes motion smoother
delay(18);
// read the value 4 times and average
ledon;
delay(1);
lsenseval = 0;
rsenseval = 0;
for(i=0; i<4; i++){
lsenseval += analogRead(lsensepin);
rsenseval += analogRead(rsensepin);
}
// don't divide by 4 because it is used below
ledoff;
// refill the random bits if needed
if(randomBits == 0){ randomBits = micros(); }
// Here is the important part
// There are four possible states: both white, both black, one of each
// The behavior will depend on current and previous states
if((lsenseval > lwhiteval*leftSensitivity) && (rsenseval > rwhiteval*rightSensitivity)){
// both white - if prior turn toward black, else random walk
if(lastSense == 2 || millis() < prior){
// turn toward last black or left
if(priorDir == 0){
moveEndTime = millis()+smallturn;
move(0, rspd); // turn left
lastMove = 1;
}else if(priorDir == 1){
moveEndTime = millis()+smallturn;
move(lspd, 0); // turn right
lastMove = 2;
}else{
moveEndTime = millis()+bigturn;
move(0, rspd); // turn left a lot
lastMove = 1;
}
}else{
// random walk
if(millis() < moveEndTime){
// just continue moving
}else{
if(lastMove){
moveEndTime = millis()+steplength;
move(lspd, rspd); // go straight
lastMove = 0;
}else{
if(randomBits & 1){
moveEndTime = millis()+smallturn;
move(0, rspd); // turn left
lastMove = 1;
}else{
moveEndTime = millis()+smallturn;
move(lspd, 0); // turn right
lastMove = 2;
}
randomBits >>= 1;
}
}
}
lastSense = 1;
}else if((lsenseval > lwhiteval*leftSensitivity) || (rsenseval > rwhiteval*rightSensitivity)){
// one white, one black - this is the edge
// just go straight
moveEndTime = millis()+steplength;
move(lspd, rspd); // go straight
lastMove = 0;
lastSense = 0;
prior = millis()+memtime;
if(lsenseval > lwhiteval*leftSensitivity){
// the right one is black
priorDir = 1;
}else{
// the left one is black
priorDir = 0;
}
}else{
// both black - if prior turn toward white, else random walk
if(lastSense == 1 || millis() < prior){
// turn toward last white or left
if(priorDir == 0){
moveEndTime = millis()+smallturn;
move(lspd, 0); // turn right
lastMove = 2;
}else if(priorDir == 1){
moveEndTime = millis()+smallturn;
move(0, rspd); // turn left
lastMove = 1;
}else{
moveEndTime = millis()+bigturn;
move(lspd, 0); // turn right a lot
lastMove = 2;
}
}else{
// random walk
if(millis() < moveEndTime){
// just continue moving
}else{
if(lastMove){
moveEndTime = millis()+steplength;
move(lspd, rspd); // go straight
lastMove = 0;
}else{
if(randomBits & 1){
moveEndTime = millis()+smallturn;
move(0, rspd); // turn left
lastMove = 1;
}else{
moveEndTime = millis()+smallturn;
move(lspd, 0); // turn right
lastMove = 2;
}
randomBits >>= 1;
}
}
}
lastSense = 2;
}
}
}
void move(uint8_t lspeed, uint8_t rspeed){
analogWrite(lmotorpin, lspeed);
analogWrite(rmotorpin, rspeed);
}
void stop(){
analogWrite(lmotorpin, 0);
analogWrite(rmotorpin, 0);
}
// stores the average of 16 readings as a white value
void senseInit(){
lwhiteval = 0;
rwhiteval = 0;
ledon;
delay(1);
for(uint8_t i=0; i<16; i++){
lwhiteval += analogRead(lsensepin);
delay(1);
rwhiteval += analogRead(rsensepin);
delay(9);
}
lwhiteval >>= 4;
rwhiteval >>= 4;
ledoff;
}
void flashLED(uint8_t flashes){
while(flashes){
flashes--;
ledon;
delay(200);
ledoff;
if(flashes){ delay(500); }
}
}