-
Notifications
You must be signed in to change notification settings - Fork 0
/
line_follow_function.py
281 lines (226 loc) · 7.31 KB
/
line_follow_function.py
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
import Adafruit_BBIO.UART as UART
import serial
import Adafruit_BBIO.PWM as PWM
import Adafruit_BBIO.GPIO as GPIO
import PID
import time
def getLinePos(sensorVals):
"This function calculates the position of the line wrt the line following board"
sumNum = 0
numCoeff = 0
sumDem = 1
for x in sensorVals:
if x > 400:
sumDem = sumDem + x
sumNum = sumNum + numCoeff*x
numCoeff = numCoeff + 1000
location = sumNum/sumDem
return location
def getSensorVals(ser):
ser.open()
sensorVals = []
sum = 0
if ser.isOpen():
ser.write("1")
line = ser.readline()
if line[0] == "0":
strWColon= line.split(" ")
for x in strWColon:
lsh, rhs = x.split(":")
rhs = float(rhs)
rhs = 1000-rhs #comment this line out if it is black line on white paper
sensorVals.append(rhs)
ser.close()
return sensorVals
def getMotorspeeds(base_speed, p, currpos):
motorval = p.update(currpos)
m1Speed = base_speed + motorval
m2Speed = base_speed - motorval
if m1Speed < 10:
m1Speed = 10
if m2Speed < 10:
m2Speed = 10
if m1Speed > 100:
m1Speed = 100
if m2Speed > 100:
m2Speed = 100
return (m1Speed, m2Speed)
def setMotorspeed(Left_Motor_Pin, Right_Motor_Pin, LeftMotor_speed, RightMotor_speed):
PWM.set_duty_cycle(Left_Motor_Pin, LeftMotor_speed)
PWM.set_duty_cycle(Right_Motor_Pin, RightMotor_speed)
return
def detectTurn(line, threshold):
if line[0] > threshold and line[1] > threshold and line[2] > threshold and line[3] > threshold:
return "right"
if line[10] > threshold and line[11] > threshold and line[12] > threshold and line[13] > threshold:
return "left"
return "none"
def detectEvent(line, threshold, eventCount):
for x in line:
if x < threshold:
return False, eventCount
eventCount += 1
print "event Found!!!!"
return True, eventCount
def turnLeft():
turn_speed = 15
GPIO.output(Left_Motor_Direction, GPIO.LOW) #set left motor to go backwards.
GPIO.output(Right_Motor_Direction, GPIO.HIGH)
PWM.set_duty_cycle(Left_Motor_Pin, turn_speed)
PWM.set_duty_cycle(Right_Motor_Pin, turn_speed)
time.sleep(1) #wait one second for turn
GPIO.output(Left_Motor_Direction, GPIO.HIGH) #set left motor back to forwards direction
def turnRight():
turn_speed = 15
GPIO.output(Right_Motor_Direction, GPIO.LOW) #set right motor to go backwards.
GPIO.output(Left_Motor_Direction, GPIO.HIGH) #set left to go forwards
PWM.set_duty_cycle(Left_Motor_Pin, turn_speed)
PWM.set_duty_cycle(Right_Motor_Pin, turn_speed)
time.sleep(1) #wait one second for turn
GPIO.output(Left_Motor_Direction, GPIO.HIGH) #set left motor back to forwards direction
def stayStragightUntilOutOfBox():
base_speed = 15
GPIO.output(Left_Motor_Direction, GPIO.HIGH) #set left motor to go forward.
GPIO.output(Right_Motor_Direction, GPIO.HIGH) #right motor forward
sensorVals = getSensorVals(ser)
while sensorVals < 14 * [black_line]: #keep going until one of the sensors reads a black line.
PWM.set_duty_cycle(Left_Motor_Pin, base_speed)
PWM.set_duty_cycle(Right_Motor_Pin, base_speed)
PWM.set_duty_cycle(Left_Motor_Pin, 0)
PWM.set_duty_cycle(Right_Motor_Pin, 0)
return
#The recipe gives simple implementation of a Discrete Proportional-Integral-Derivative (PID) controller. PID controller gives output value for error between desired reference input and measurement feedback to minimize error value.
#More information: http://en.wikipedia.org/wiki/PID_controller
#
#cnr437@gmail.com
#
####### Example #########
#
#p=PID(3.0,0.4,1.2)
#p.setPoint(5.0)
#while True:
# pid = p.update(measurement_value)
#
#
class PID:
"""
Discrete PID control
"""
def __init__(self, P=2.0, I=0.0, D=1.0, Derivator=0, Integrator=0, Integrator_max=500, Integrator_min=-500):
self.Kp=P
self.Ki=I
self.Kd=D
self.Derivator=Derivator
self.Integrator=Integrator
self.Integrator_max=Integrator_max
self.Integrator_min=Integrator_min
self.set_point=0.0
self.error=0.0
def update(self,current_value):
"""
Calculate PID output value for given reference input and feedback
"""
self.error = self.set_point - current_value
self.P_value = self.Kp * self.error
self.D_value = self.Kd * ( self.error - self.Derivator)
self.Derivator = self.error
self.Integrator = self.Integrator + self.error
if self.Integrator > self.Integrator_max:
self.Integrator = self.Integrator_max
elif self.Integrator < self.Integrator_min:
self.Integrator = self.Integrator_min
self.I_value = self.Integrator * self.Ki
PID = self.P_value + self.I_value + self.D_value
return PID
def setPoint(self,set_point):
"""
Initilize the setpoint of PID
"""
self.set_point = set_point
self.Integrator=0
self.Derivator=0
def setIntegrator(self, Integrator):
self.Integrator = Integrator
def setDerivator(self, Derivator):
self.Derivator = Derivator
def setKp(self,P):
self.Kp=P
def setKi(self,I):
self.Ki=I
def setKd(self,D):
self.Kd=D
def getPoint(self):
return self.set_point
def getError(self):
return self.error
def getIntegrator(self):
return self.Integrator
def getDerivator(self):
return self.Derivator
UART.setup("UART4")
Left_Motor_Pin = "P8_19"
Right_Motor_Pin = "P9_14"
Left_Motor_Direction = "P9_26"
Right_Motor_Direction = "P9_25"
Start_Detection = "P8_7"
ser = serial.Serial(port = "/dev/ttyO4", baudrate = 9600)
GPIO.setup(Left_Motor_Direction, GPIO.OUT)
GPIO.setup(Right_Motor_Direction, GPIO.OUT)
GPIO.setup(Start_Detection,GPIO.IN)
PWM.start(Left_Motor_Pin, 0.0, 20000, 1) #Motor 1 (Left)
PWM.start(Right_Motor_Pin, 0.0, 20000, 1) #Motor 2 (Right)
p = PID(0.001,0.0,0.0) # set up PID with KP, KI, KD
p.setPoint(6500) #setpoint to middle of device.
black_line = 200
GPIO.output(Left_Motor_Direction, GPIO.HIGH)
GPIO.output(Right_Motor_Direction, GPIO.HIGH)
var = 1
base_speed = 15
eventCount = 0
#time.sleep(5) #wait for calibration of line follower
#1 = dont go (LED on)
#0 = go (LED off)
#Start detection below
while GPIO.input(Start_Detection)==1: #loop while LED is on.
print "waiting for LED to turn off"
time.sleep(0.1)
#LED off. Now start code.
while var == 1 :
sensorVals = getSensorVals(ser)
linePos = getLinePos(sensorVals)
eventAvailable,eventCount = detectEvent(sensorVals, 850, eventCount)
if eventAvailable:
if eventCount == 1: #in starting box. keep going direction we're going until we don't see a box anymore.
stayStragightUntilOutOfBox()
print "event Count = ", eventCount
#time.sleep(1)
elif eventCount == 2: #2nd event
print "event Count = ", eventCount
#time.sleep(1)
#etchASketch()
#turnAround()
#stayStraightUntilOutOfBox()
#continue
elif eventCount == 3: #3rd event
print "event Count = ", eventCount
#time.sleep(1)
else:
print "eventCountAboveLimit"
else: #event was not found. look for a turn
turnAvailable = detectTurn(sensorVals, 850)
if turnAvailable == "left":
print "turn Left Detected"
turnLeft()
continue
elif turnAvailable == "right":
print "turn Right detected"
turnRight()
continue
LeftMotor_speed, RightMotor_speed = getMotorspeeds(base_speed, p, linePos)
setMotorspeed(Left_Motor_Pin, Right_Motor_Pin, LeftMotor_speed, RightMotor_speed)
start_detection = GPIO.input("P8_7")
print "Start: ", start_detection
print sensorVals
print "Line position = ", linePos
print 'Left MS: ', LeftMotor_speed
print 'Right MS: ', RightMotor_speed