-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathDILLIGAF.ino
386 lines (292 loc) · 10.9 KB
/
DILLIGAF.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
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
/*
██▒ █▓ ▒█████ ▒█████ ▓█████▄ ▒█████ ▒█████
▓██░ █▒▒██▒ ██▒▒██▒ ██▒ ▒██▀ ██▌▒██▒ ██▒▒██▒ ██▒
▓██ █▒░▒██░ ██▒▒██░ ██▒ ░██ █▌▒██░ ██▒▒██░ ██▒
▒██ █░░▒██ ██░▒██ ██░▒░▓█▄ ▌▒██ ██░▒██ ██░
▒▀█░ ░ ████▓▒░░ ████▓▒░░░▒████▓ ░ ████▓▒░░ ████▓▒░
░ ▐░ ░ ▒░▒░▒░ ░ ▒░▒░▒░ ░ ▒▒▓ ▒ ░ ▒░▒░▒░ ░ ▒░▒░▒░
░ ░░ ░ ▒ ▒░ ░ ▒ ▒░ ░ ▒ ▒ ░ ▒ ▒░ ░ ▒ ▒░
░░ ░ ░ ░ ▒ ░ ░ ░ ▒ ░ ░ ░ ░ ░ ░ ▒ ░ ░ ░ ▒
░ ░ ░ ░ ░ ░ ░ ░ ░ ░
$ Author: Risha $
$ Revision: 0.9 $
PascalCase - Pins
camelCase - Variables
snake_case - Functions
== TODO ==
-
*/
/*===============================================================
LIBRARIES
===============================================================*/
#include "DILLIGAF.h" // import the header file which contains the sensors' pins & global variables
#include "MOTOR.h" // import the motor driver pins & functions
/*===============================================================
SETUP
===============================================================*/
void setup() {
// put your setup code here, to run once:
set_pwm_frequency(LeftMotorPwm, 8); // (pin,divisor)
set_pwm_frequency(RightMotorPwm, 8); // (pin,divisor)
// ======= OUTPUTS ======= //
pinMode(LeftMotorPwm, OUTPUT);
pinMode(RightMotorPwm, OUTPUT);
pinMode(LeftMotorEnable, OUTPUT);
pinMode(RightMotorEnable, OUTPUT);
// ======= INPUTS ======= //
pinMode(LeftSensor, INPUT);
pinMode(FrontLeftSensor, INPUT);
pinMode(FrontMiddleSensor, INPUT);
pinMode(FrontRightSensor, INPUT);
pinMode(RightSensor, INPUT);
pinMode(PushButton, INPUT_PULLUP);
pinMode(DipSwitch1, INPUT_PULLUP);
pinMode(DipSwitch2, INPUT_PULLUP);
pinMode(DipSwitch3, INPUT_PULLUP);
pinMode(DipSwitch4, INPUT_PULLUP);
// ======= Activate Sensors ======= //
digitalWrite(LeftSensor, HIGH);
digitalWrite(FrontLeftSensor, HIGH);
digitalWrite(FrontMiddleSensor, HIGH);
digitalWrite(FrontRightSensor, HIGH);
digitalWrite(RightSensor, HIGH);
// ======= Strategy ======= //
dipNum = dip_switch();
// Serial.begin(9600);
}
/*===============================================================
Line Control
===============================================================*/
void line_control() {
/*
Description
----------
This function controls the behavior of the robot based on edge sensor readings.
It uses analog readings from front and back edge sensors to make decisions and adjust the robot's movement.
Behavior
----------
- The function checks the readings from the front left, front right and back edge sensors.
- If a white edge is detected on the left side, the robot performs a backward maneuver, followed by a right turn.
- If a white edge is detected on the right side, the robot performs a backward maneuver, followed by a left turn.
- If white edges are detected on both front sides, the robot performs a backward maneuver, followed by a sharp 180 turn.
- If a white edge is detected on the back side, the robot moves forward at full speed.
- Brakes are added at appropriate stages to enhance maneuvering control.
*/
if (analogRead(FrontLeftEdge) < whiteValue && analogRead(FrontRightEdge) > blackValue) {
// white edge on the left side
delay(8);
if (analogRead(FrontLeftEdge) < whiteValue) {
go_backward(1000);
brake(50);
turn_right(1200);
brake(50);
}
}
else if (analogRead(FrontLeftEdge) > blackValue && analogRead(FrontRightEdge) < whiteValue) {
// white edge on the right side
delay(8);
if (analogRead(FrontRightEdge) < whiteValue) {
go_backward(1000);
brake(50);
turn_left(1200);
brake(50);
}
}
else if (analogRead(FrontLeftEdge) < whiteValue && analogRead(FrontRightEdge) < whiteValue) {
// white edge on the both front sides
delay(8);
if (analogRead(FrontLeftEdge) < whiteValue && analogRead(FrontRightEdge) < whiteValue) {
go_backward(1000);
brake(50);
turn_right(1200);
brake(50);
}
}
else if (analogRead(FrontLeftEdge) > blackValue && analogRead(FrontRightEdge) > blackValue && analogRead(BackEdge) < whiteValue) {
// white edge on the back side
delay(8);
if (analogRead(BackEdge) < whiteValue) {
go_forward(1200);
brake(50);
}
}
}
/*===============================================================
Hunt (Attack)
===============================================================*/
void hunt() {
/*
Description:
------------
This function implements a behavior for a robot or vehicle. It combines line following, edge detection,
and sensor readings to navigate and react to different scenarios.
Behavior:
----------
- If any of the edge sensors (`FrontLeftEdge`, `FrontRightEdge`, or `BackEdge`) detect a value lower than `whiteValue`, the `line_control()` function is called to follow the line.
- If the `FrontMiddleSensor` is HIGH, the robot goes forward and `lastSensorValue` is set to 1.
- If the `FrontLeftSensor` is HIGH, the robot is turned right and `lastSensorValue` is set to 2.
- If the `FrontRightSensor` is HIGH, the robot is turned left and `lastSensorValue` is set to 3.
- If the `LeftSensor` is HIGH, the robot is turned left and `lastSensorValue` is set to 3.
- If the `RightSensor` is HIGH, the robot is turned right and `lastSensorValue` is set to 2.
- If none of the above conditions are met, the function checks the value of `lastSensorValue` to determine the appropriate motor control actions:
- If `lastSensorValue` is 1, the robot is controlled to move forward with equal motor speeds.
- If `lastSensorValue` is 2, the robot is controlled to move backward and turn slightly to the right.
- If `lastSensorValue` is 3, the robot is controlled to move forward and turn slightly to the left.
*/
if (analogRead(FrontLeftEdge) < whiteValue || analogRead(FrontRightEdge) < whiteValue || analogRead(BackEdge) < whiteValue) {
line_control();
}
else if (digitalRead(FrontMiddleSensor) == HIGH) {
delay(8);
if (digitalRead(FrontMiddleSensor) == HIGH) {
go_forward(-1);
lastSensorValue = 1;
}
}
else if (digitalRead(FrontLeftSensor) == HIGH) {
delay(8);
if (digitalRead(FrontLeftSensor) == HIGH) {
turn_right(-1);
lastSensorValue = 2;
}
}
else if (digitalRead(FrontRightSensor) == HIGH) {
delay(8);
if (digitalRead(FrontRightSensor) == HIGH) {
turn_left(-1);
lastSensorValue = 3;
}
}
else if (digitalRead(LeftSensor) == HIGH) {
delay(8);
if (digitalRead(LeftSensor) == HIGH) {
turn_left(-1);
lastSensorValue = 3;
}
}
else if (digitalRead(RightSensor) == HIGH) {
delay(8);
if (digitalRead(RightSensor) == HIGH) {
turn_right(-1);
lastSensorValue = 2;
}
}
else {
if (lastSensorValue == 1) {
motor_control(220, 220);
}
else if (lastSensorValue == 2) {
motor_control(200, -150);
}
else if (lastSensorValue == 3) {
motor_control(-150, 200);
}
}
}
/*===============================================================
MAIN LOOP
===============================================================*/
void loop() {
// put your main code here, to run repeatedly:
if (digitalRead(PushButton) == LOW && !buttonPressed && !robotOn) {
buttonPressTime = millis();
buttonPressed = true;
}
else if (digitalRead(PushButton) == LOW && !buttonPressed && robotOn) {
stop(1000);
robotOn = false;
buttonPressed = false;
}
else if (buttonPressed && (millis() - buttonPressTime) >= 5000) {
robotOn = true;
buttonPressed = false;
}
if (robotOn) {
lastSensorValue = 3;
switch (dipNum) {
case 0: // Testing
sensor_debug();
motor_debugging();
break;
case 1: // Direct Forward Attack
while (digitalRead(PushButton) != LOW) {
motor_control(250, 250); delay(3000);
motor_control(1, 1); delay(500);
motor_control(-250, -250); delay(3000);
motor_control(1, 1); delay(40000);
}
break;
case 2: // Left Arc
motor_control(-250, 250); delay(560);
motor_control(1, 1); delay(50);
motor_control(250, 250); delay(800);
motor_control(1, 1); delay(50);
motor_control(250, 140); delay(1600);
motor_control(1, 1); delay(50);
motor_control(250, -250); delay(400);
break;
case 3: // Right Arc
motor_control(250, -250); delay(500);
brake(50);
motor_control(250, 250); delay(800);
brake(50);
motor_control(150, 250); delay(1600);
brake(50);
motor_control(-250, 250); delay(600);
break;
case 4: // Left Zig-Zag
motor_control(-250, 250); delay(700);
motor_control(1, 1); delay(50);
motor_control(250, 250); delay(1900);
motor_control(1, 1); delay(50);
motor_control(250, -250); delay(400);
motor_control(1, 1); delay(50);
motor_control(250, 250); delay(1200);
break;
case 5: // Right Zig-Zag
motor_control(250, -250); delay(400);
motor_control(1, 1); delay(50);
motor_control(250, 250); delay(1600);
motor_control(1, 1); delay(50);
motor_control(-250, 250); delay(1200);
motor_control(1, 1); delay(50);
motor_control(250, 250); delay(1200);
break;
case 6: // Down Down Down
motor_control(250, 250); delay(600);
motor_control(1, 1); delay(100);
motor_control(-250, -250); delay(600);
motor_control(250, 250); delay(600);
motor_control(1, 1); delay(100);
motor_control(-250, -250); delay(600);
motor_control(250, 250); delay(600);
motor_control(1, 1); delay(100);
motor_control(-250, -250); delay(600);
motor_control (250, 250); delay(1200);
break;
case 7:
break;
case 8:
break;
case 9:
break;
case 10:
break;
case 11:
break;
case 12:
break;
case 13:
break;
case 14:
break;
case 15:
break;
default:
break;
}
while (digitalRead(PushButton) != LOW) {
hunt();
}
}
}