-
Notifications
You must be signed in to change notification settings - Fork 0
/
automatic.cpp
388 lines (322 loc) · 9.31 KB
/
automatic.cpp
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
386
387
388
#include "automatic.h"
Automatic::Automatic()
{
check = false;
error = 0;
}
void Automatic::setInputSensor(float p)
{
dist_obs = p;
Automatic::CheckObstacle();
}
void Automatic::setInputLine(uint8_t pDX,
uint8_t pSX)
{
sensorStateDX = pDX;
sensorStateSX = pSX;
Automatic::ReadPath();
Automatic::PathError();
}
int Automatic::getPathError() { return error; }
bool Automatic::getCheckObstacle() { return check; }
void Automatic::CheckObstacle()
{
//Serial.print("distanza: ");
//Serial.print(dist_obs);
//Serial.println(" cm");
if (dist_obs >= 15.00 || dist_obs == 0.0) check = true;
else check = false;
}
void Automatic::ReadPath()
{
if(sensorStateDX == 1 && sensorStateSX == 2)
{
input_path = 1;
//Serial.print("sensor input, ");
//Serial.println(input_path);
} //GO_FORWARD
else if(sensorStateDX == 3 && sensorStateSX == 2)
{
input_path = 2;
//Serial.print("sensor input, ");
//Serial.println(input_path);
}//TURN_LEFT_VERY_SOFT
else if(sensorStateDX == 1 && sensorStateSX == 0)
{
input_path = 3;
//Serial.print("sensor input, ");
//Serial.println(input_path);
} //TURN_LEFT_SOFT
else if(sensorStateDX == 3 && sensorStateSX == 0)
{
input_path = 4;
//Serial.print("sensor input, ");
//Serial.println(input_path);
} //TURN_LEFT_HARD
else if(sensorStateDX == 3 && sensorStateSX == 1)
{
input_path = 5;
//Serial.print("sensor input, ");
//Serial.println(input_path);
} //TURN_LEFT_VERYHARD
else if(sensorStateDX == 1 && sensorStateSX == 3)
{
input_path = 6;
//Serial.print("sensor input, ");
//Serial.println(input_path);
} //TURN_RIGHT_VERY_SOFT
else if(sensorStateDX == 0 && sensorStateSX == 2)
{
input_path = 7;
//Serial.print("sensor input, ");
//Serial.println(input_path);
} //TURN_RIGHT_SOFT
else if(sensorStateDX == 0 && sensorStateSX == 3)
{
input_path = 8;
//Serial.print("sensor input, ");
//Serial.println(input_path);
} //TURN_RIGHT_HARD
else if(sensorStateDX == 2 && sensorStateSX == 3)
{
input_path = 9;
//Serial.print("sensor input, ");
//Serial.println(input_path);
} //TURN_RIGHT_VERYHARD
else if(sensorStateDX == 3 && sensorStateSX == 3)
{
input_path = 10;
//Serial.print("sensor input, ");
//Serial.println(input_path);
} //NO_LINE
else if(sensorStateDX == 2 && sensorStateSX == 0)
{
input_path = 11;
//Serial.print("sensor input, ");
//Serial.println(input_path);
} //EXCEPTION1
else if(sensorStateDX == 0 && sensorStateSX == 1)
{
input_path = 12;
//Serial.print("sensor input, ");
//Serial.println(input_path);
} //EXCEPTION2
else if(sensorStateDX == 2 && sensorStateSX == 1)
{
input_path = 13;
//Serial.print("sensor input, ");
//Serial.println(input_path);
} //GO_FORWARD_bis
else if(sensorStateDX == 0 && sensorStateSX == 0)
{
input_path = 14;
//Serial.print("sensor input, ");
//Serial.println(input_path);
} //CROSS
else if(sensorStateDX == 2 && sensorStateSX == 2)
{
input_path = 15;
//Serial.print("sensor input, ");
//Serial.println(input_path);
} //EXCEPTION3
else if(sensorStateDX == 1 && sensorStateSX == 1)
{
input_path = 16;
//Serial.print("sensor input, ");
//Serial.println(input_path);
} //EXCEPTION4
}
/*FUNZIONE path_error
in questa funzione in ingresso vengono ricevuti
due interi ricavati dai metodi dei line follewer
e in uscita viene restituito un intero che individua la posizione del
robot rispetto alla linea da seguire (error = output - setpoint).
Sulla base dei valori ricevuti dai sensori si ottengono i seguenti casi:
(X=nero; O=bianco)
DX SX SX DX Error
GO_FORWARD == 1 , 2 O X X O 0 (line = nero & background = bianco)
TURN_LEFT_VERY_SOFT == 3 , 2 O X O O 1
TURN_LEFT_SOFT == 1 , 0 X X X O 2
TURN_LEFT_HARD == 3 , 0 X X O O 3
TURN_LEFT_VERYHARD == 3 , 1 X O O O 4
TURN_RIGHT_VERY_SOFT == 1 , 3 O O X O -1
TURN_RIGHT_SOFT == 0 , 2 O X X X -2
TURN_RIGHT_HARD == 0 , 3 O O X X -3
TURN_RIGHT_VERYHARD == 2 , 3 O O O X -4
NO_LINE == 3 , 3 O O O O 5
EXCEPTION1 == 2 , 0 X X O X 1
EXCEPTION2 == 0 , 1 X O X X -1
GO_FORWARD_bis == 2 , 1 X O O X 0
CROSS == 0 , 0 X X X X 6
EXCEPTION3 == 2 , 2 O X O X 0
EXCEPTION4 == 1 , 1 X O X O 0
*/
void Automatic::PathError()
{
switch(input_path)
{
case 1:
//attribusico l'errore da calcolare poi nella funzione PID
error = 0;
//stampa sulla //Seriale per debugging
//Serial.print("GO_FORWARD");
//Serial.print(", ");
//Serial.print(input_path);
//Serial.print(", error: ");
//Serial.println(error);
break;
case 2:
//attribusico l'errore da calcolare poi nella funzione PID
error = 1;
//stampa sulla //Seriale per debugging
//Serial.print("TURN_LEFT_VERY_SOFT");
//Serial.print(", ");
//Serial.print(input_path);
//Serial.print(", error: ");
//Serial.println(error);
break;
case 3 :
//attribusico l'errore da calcolare poi nella funzione PID
error = 2;
//stampa sulla //Seriale per debugging
//Serial.print("TURN_LEFT_SOFT ");
//Serial.print(", ");
//Serial.print(input_path);
//Serial.print(", error: ");
//Serial.println(error);
break;
case 4:
//attribusico l'errore da calcolare poi nella funzione PID
error = 3;
//stampa sulla //Seriale per debugging
//Serial.print("TURN_LEFT_HARD");
//Serial.print(", ");
//Serial.print(input_path);
//Serial.print(", error: ");
//Serial.println(error);
break;
case 5:
//attribusico l'errore da calcolare poi nella funzione PID
error = 4;
//stampa sulla //Seriale per debugging
//Serial.print("TURN_LEFT_VERYHARD");
//Serial.print(", ");
//Serial.print(input_path);
//Serial.print(", error: ");
//Serial.println(error);
break;
case 6:
//attribusico l'errore da calcolare poi nella funzione PID
error = -1;
//stampa sulla //Seriale per debugging
//Serial.print("TURN_RIGHT_VERY_SOFT");
//Serial.print(", ");
//Serial.print(input_path);
//Serial.print(", error: ");
//Serial.println(error);
break;
case 7:
//attribusico l'errore da calcolare poi nella funzione PID
error = -2;
//stampa sulla //Seriale per debugging
//Serial.print("TURN_RIGHT_SOFT");
//Serial.print(", ");
//Serial.print(input_path);
//Serial.print(", error: ");
//Serial.println(error);
break;
case 8:
//attribusico l'errore da calcolare poi nella funzione PID
error = -3;
//stampa sulla //Seriale per debugging
//Serial.print("TURN_RIGHT_HARD");
//Serial.print(", ");
//Serial.print(input_path);
//Serial.print(", error: ");
//Serial.println(error);
break;
case 9:
//attribusico l'errore da calcolare poi nella funzione PID
error = -4;
//stampa sulla //Seriale per debugging
//Serial.print("TURN_RIGHT_VERYHARD");
//Serial.print(", ");
//Serial.print(input_path);
//Serial.print(", error: ");
//Serial.println(error);
break;
case 10:
//attribusico l'errore da calcolare poi nella funzione PID
error = 5;
//stampa sulla //Seriale per debugging
//Serial.print("case 10");
//Serial.print(", ");
//Serial.print(input_path);
//Serial.print(", error: ");
//Serial.println(error);
break;
case 11:
//attribusico l'errore da calcolare poi nella funzione PID
error = 1;
//stampa sulla //Seriale per debugging
//Serial.print("case 11");
//Serial.print(", ");
//Serial.print(input_path);
//Serial.print(", error: ");
//Serial.println(error);
break;
case 12:
//attribusico l'errore da calcolare poi nella funzione PID
error = -1;
//stampa sulla //Seriale per debugging
//Serial.print("case 12");
//Serial.print(", ");
//Serial.print(input_path);
//Serial.print(", error: ");
//Serial.println(error);
break;
case 13:
//attribusico l'errore da calcolare poi nella funzione PID
error = 0;
//stampa sulla //Seriale per debugging
//Serial.print("case 13");
//Serial.print(", ");
//Serial.print(input_path);
//Serial.print(", error: ");
//Serial.println(error);
break;
case 14:
//attribusico l'errore da calcolare poi nella funzione PID
error = 6;
//stampa sulla //Seriale per debugging
//Serial.print("case 14");
//Serial.print(", ");
//Serial.print(input_path);
//Serial.print(", error: ");
//Serial.println(error);
break;
case 15:
//attribusico l'errore da calcolare poi nella funzione PID
error =0 ;
//stampa sulla //Seriale per debugging
//Serial.print("case 15");
//Serial.print(", ");
//Serial.print(input_path);
//Serial.print(", error: ");
//Serial.println(error);
break;
case 16:
//attribusico l'errore da calcolare poi nella funzione PID
error = 0;
//stampa sulla //Seriale per debugging
//Serial.print("case 16");
//Serial.print(", ");
//Serial.print(input_path);
//Serial.print(", error: ");
//Serial.println(error);
break;
default:
exit;
break;
}
}