-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathreal_sercan_bot2.cpp
219 lines (179 loc) · 6.89 KB
/
real_sercan_bot2.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
#include <QTRSensors.h>
QTRSensors qtr;
const uint8_t SensorCount = 8;
uint16_t sensorValues[SensorCount];
#define turnspeed 100
#define Kp 0.1 // bunu belirlemek için deney yapın, botunuzun çizgiyi yavaş bir hızda takip etmesini sağlayan küçük bir şeyle başlayın
#define Kd 0.7 // bunu belirlemek için deney yapın, hızları yavaşça artırın ve bu değeri ayarlayın. ( Not: Kp < Kd)
#define rightMaxSpeed 85 // max speed of the robot
#define leftMaxSpeed 85 // max speed of the robot
#define rightBaseSpeed 60 // this is the speed at which the motors should spin when the robot is perfectly on the line
#define leftBaseSpeed 60 // this is the speed at which the motors should spin when the robot is perfectly on the line
#define NUM_SENSORS 8 // number of sensors used
#define TIMEOUT 2500 // waits for 2500 us for sensor outputs to go low
#define EMITTER_PIN 2 // emitter is controlled by digital pin 2
#define solMotorPWM 6
#define sagMotorPWM 11
#define solOnIleriPin 2
#define solOnGeriPin 3
#define sagOnIleriPin 10
#define sagOnGeriPin 9
#define solArkaIleriPin 5
#define solArkaGeriPin 4
#define sagArkaIleriPin 8
#define sagArkaGeriPin 7
void setup()
{
pinMode(solMotorPWM,OUTPUT);
pinMode(sagMotorPWM,OUTPUT);
pinMode(solOnIleriPin,OUTPUT);
pinMode(solOnGeriPin,OUTPUT);
pinMode(sagOnIleriPin,OUTPUT);
pinMode(sagOnGeriPin,OUTPUT);
pinMode(solArkaIleriPin,OUTPUT);
pinMode(solArkaGeriPin,OUTPUT);
pinMode(sagArkaIleriPin,OUTPUT);
pinMode(sagArkaGeriPin,OUTPUT);
//Sensor ayarları
qtr.setTypeAnalog();
qtr.setSensorPins((const uint8_t[]){A0, A1, A2, A3, A4, A5, A6, A7}, SensorCount);
//qtr.setTimeout(TIMEOUT);
//qtr.setEmitterPin(2);
delay(500);
pinMode(LED_BUILTIN, OUTPUT);
digitalWrite(LED_BUILTIN, HIGH); // kalibrasyon modunda olduğumuzu belirtmek için Arduino'nun LED'ini açın
// 2,5 ms RC okuma zaman aşımı (varsayılan) * calibrate() çağrısı başına 10 okuma
// = calibrate() çağrısı başına ~25 ms.
// Kalibrasyonun yaklaşık 10 saniye sürmesi için calibrate()'i 400 kez çağırın.
for (uint16_t i = 0; i < 400; i++)
{
qtr.calibrate();
}
digitalWrite(LED_BUILTIN, LOW); // kalibrasyonun bittiğini belirtmek için Arduino'nun LED'ini kapatın
delay(500);
Serial.begin(9600);
/*for (uint8_t i = 0; i < SensorCount; i++)
{
Serial.print(qtr.calibrationOn.minimum[i]);
Serial.print(' ');
}
Serial.println();
// emitörler açıkken ölçülen kalibrasyon maksimum değerlerini yazdırın
for (uint8_t i = 0; i < SensorCount; i++)
{
Serial.print(qtr.calibrationOn.maximum[i]);
Serial.print(' ');
}
Serial.println();
Serial.println();*/
delay(1000);
}
int lastError = 0;
int sola_donus_say = 0;
int saga_donus_say = 0;
void loop() {
// kalibre edilmiş sensör değerlerini okuyun ve hat konumunun bir ölçüsünü elde edin
// 0'dan 5000'e kadar (beyaz bir çizgi için bunun yerine readLineWhite() kullanın)
uint16_t position = qtr.readLineWhite(sensorValues);
if(sensor_say(sensorValues) <= 3)//Düz yolda gitme
{
// sensör değerlerini 0'dan 1000'e kadar sayılar olarak yazdırın, burada 0 maksimum anlamına gelir
// yansıma ve 1000 minimum yansıma anlamına gelir, ardından satır gelir
// konum
/*for (uint8_t i = 0; i < SensorCount; i++)
{
Serial.print(sensorValues[i]);
Serial.print('\t');
}
Serial.println(position);
delay(100);
return;*/
//PID Hesaplama
int error = position - 3500;
int motorSpeed = Kp * error + Kd * (error - lastError);
lastError = error;
int rightMotorSpeed = rightBaseSpeed + motorSpeed;
int leftMotorSpeed = leftBaseSpeed - motorSpeed;
/*Serial.print("Sol Motor:");
Serial.print(leftMotorSpeed);
Serial.print("Sağ Motor:");
Serial.print(rightMotorSpeed);
Serial.println();*/
if (rightMotorSpeed > rightMaxSpeed ) rightMotorSpeed = rightMaxSpeed; // prevent the motor from going beyond max speed
if (leftMotorSpeed > leftMaxSpeed ) leftMotorSpeed = leftMaxSpeed; // prevent the motor from going beyond max speed
if (rightMotorSpeed < 0) rightMotorSpeed = 0; // keep the motor speed positive
if (leftMotorSpeed < 0) leftMotorSpeed = 0; // keep the motor speed positive
digitalWrite(sagOnIleriPin, HIGH);
digitalWrite(sagOnGeriPin, LOW);
digitalWrite(sagArkaIleriPin, HIGH);
digitalWrite(sagArkaGeriPin, LOW);
analogWrite(sagMotorPWM, rightMotorSpeed);
digitalWrite(solOnIleriPin, HIGH);
digitalWrite(solOnGeriPin, LOW);
digitalWrite(solArkaIleriPin, HIGH);
digitalWrite(solArkaGeriPin, LOW);
analogWrite(solMotorPWM, leftMotorSpeed);
}
//--------------------------------------------------------------------------------------------------------------------
//--------------------------------------------------------------------------------------------------------------------
else if(sensor_say(sensorValues)>3 and solmu_sagmi(sensorValues) == "sol")//Sola dönme kodu
{
if (sola_donus_say > 0)
{
digitalWrite(sagOnIleriPin, HIGH);
digitalWrite(sagOnGeriPin, LOW);
digitalWrite(sagArkaIleriPin, HIGH);
digitalWrite(sagArkaGeriPin, LOW);
analogWrite(sagMotorPWM, turnspeed);
digitalWrite(solOnIleriPin, LOW);
digitalWrite(solOnGeriPin, HIGH);
digitalWrite(solArkaIleriPin, LOW);
digitalWrite(solArkaGeriPin, HIGH);
analogWrite(solMotorPWM, turnspeed);
delay(350);
}
sola_donus_say += 1;
return;
}
else if (sensor_say(sensorValues)>3 and solmu_sagmi(sensorValues) == "sag")//Sağ dönme kodu
{
digitalWrite(sagOnIleriPin, LOW);
digitalWrite(sagOnGeriPin, HIGH);
digitalWrite(sagArkaIleriPin, LOW);
digitalWrite(sagArkaGeriPin, HIGH);
analogWrite(sagMotorPWM, turnspeed);
digitalWrite(solOnIleriPin, HIGH);
digitalWrite(solOnGeriPin, LOW);
digitalWrite(solArkaIleriPin, HIGH);
digitalWrite(solArkaGeriPin, LOW);
analogWrite(solMotorPWM, turnspeed);
delay(350);
saga_donus_say += 1;
return;
}
//--------------------------------------------------------------------------------------------------------------------
//--------------------------------------------------------------------------------------------------------------------
}//Loop ana Program sonu
//Alt Programlar
uint16_t sensor_say(uint16_t sV[SensorCount])
{
uint16_t say = 0;
for (uint8_t i = 0; i < SensorCount; i++)
if(sV[i] < 500) say++;
return say;
}
String solmu_sagmi(uint16_t sV[SensorCount])
{
String string_yon = "";
int sol_toplam = 0;
int sag_toplam = 0;
for (uint8_t i = 0; i < int(SensorCount/2); i++)
sol_toplam += sV[i];
for (uint8_t i = (SensorCount/2); i < (SensorCount); i++)
sag_toplam += sV[i];
if (sol_toplam < sag_toplam)
string_yon = "sag";
else if (sol_toplam > sag_toplam)
string_yon = "sol";
return string_yon;
}