-
Notifications
You must be signed in to change notification settings - Fork 0
/
easygopigo.py
executable file
·407 lines (335 loc) · 10.9 KB
/
easygopigo.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
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
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
#!/usr/bin/env python
from __future__ import print_function
from __future__ import division
from builtins import input
import sys
import tty
import select
import gopigo
sys.path.insert(0, '/home/pi/Desktop/GoPiGo/Software/Python/line_follower')
import line_sensor
import scratch_line
# IR Receiver
try:
import ir_receiver
import ir_receiver_check
IR_RECEIVER_ENABLED = True
except:
IR_RECEIVER_ENABLED = False
old_settings = ''
fd = ''
gpg_debug = False
##########################
def debug(in_str):
'''
'''
if gpg_debug:
print(in_str)
#############################################################
# the following is in a try/except structure because it depends
# on the date of gopigo.py
#############################################################
try:
PORTS = {"A1": gopigo.analogPort, "D11": gopigo.digitalPort,
"SERIAL": -1, "I2C": -2}
except:
PORTS = {"A1": 15, "D11": 10, "SERIAL": -1, "I2C": -2}
ANALOG = 1
DIGITAL = 0
SERIAL = -1
I2C = -2
##########################
class Sensor():
'''
Base class for all sensors
Class Attributes:
port : string - user-readable port identification
portID : integer - actual port id
pinmode : "INPUT" or "OUTPUT"
pin : 1 for ANALOG, 0 for DIGITAL
descriptor = string to describe the sensor for printing purposes
Class methods:
setPort / getPort
setPinMode / getPinMode
isAnalog
isDigital
'''
def __init__(self, port, pinmode):
'''
port = one of PORTS keys
pinmode = "INPUT", "OUTPUT", "SERIAL" (which gets ignored)
'''
debug("Sensor init")
debug(pinmode)
self.setPort(port)
self.setPinMode(pinmode)
if pinmode == "INPUT" or pinmode == "OUTPUT":
gopigo.pinMode(self.getPortID(), self.getPinMode())
def __str__(self):
return ("{} on port {}".format(self.descriptor, self.getPort()))
def setPort(self, port):
self.port = port
self.portID = PORTS[self.port]
def getPort(self):
return (self.port)
def getPortID(self):
return (self.portID)
def setPinMode(self, pinmode):
self.pinmode = pinmode
def getPinMode(self):
return (self.pinmode)
def isAnalog(self):
return (self.pin == ANALOG)
def isDigital(self):
return (self.pin == DIGITAL)
def set_descriptor(self, descriptor):
self.descriptor = descriptor
##########################
class DigitalSensor(Sensor):
'''
Implements read and write methods
'''
def __init__(self, port, pinmode):
debug("DigitalSensor init")
self.pin = DIGITAL
Sensor.__init__(self, port, pinmode)
def read(self):
'''
tries to get a value up to 10 times.
As soon as a valid value is read, it returns either 0 or 1
returns -1 after 10 unsuccessful tries
'''
okay = False
error_count = 0
while not okay and error_count < 10:
try:
rtn = int(gopigo.digitalRead(self.getPortID()))
okay = True
except:
error_count += 1
if error_count > 10:
return -1
else:
return rtn
def write(self, power):
self.value = power
return gopigo.digitalWrite(self.getPortID(), power)
##########################
class AnalogSensor(Sensor):
'''
implements read and write methods
'''
def __init__(self, port, pinmode):
debug("AnalogSensor init")
self.value = 0
self.pin = ANALOG
Sensor.__init__(self, port, pinmode)
def read(self):
self.value = gopigo.analogRead(self.getPortID())
return self.value
def write(self, power):
self.value = power
return gopigo.analogWrite(self.getPortID(), power)
##########################
class LightSensor(AnalogSensor):
"""
Creates a light sensor from which we can read.
Light sensor is by default on pin A1(A-one)
self.pin takes a value of 0 when on analog pin (default value)
takes a value of 1 when on digital pin
"""
def __init__(self, port="A1"):
debug("LightSensor init")
AnalogSensor.__init__(self, port, "INPUT")
self.set_descriptor("Light sensor")
##########################
class SoundSensor(AnalogSensor):
"""
Creates a sound sensor
"""
def __init__(self, port="A1"):
debug("Sound Sensor on port "+port)
AnalogSensor.__init__(self, port, "INPUT")
self.set_descriptor("Sound sensor")
##########################
class UltraSonicSensor(AnalogSensor):
def __init__(self, port="A1"):
debug("Ultrasonic Sensor on port "+port)
AnalogSensor.__init__(self, port, "INPUT")
self.safe_distance = 500
self.set_descriptor("Ultrasonic sensor")
def is_too_close(self):
if gopigo.us_dist(PORTS[self.port]) < self.get_safe_distance():
return True
return False
def set_safe_distance(self, dist):
self.safe_distance = int(dist)
def get_safe_distance(self):
return self.safe_distance
def read(self):
return gopigo.us_dist(PORTS[self.port])
##########################
class Buzzer(AnalogSensor):
'''
The Buzzer class is a digital Sensor with power modulation (PWM).
Default port is D11
Note that it inherits from AnalogSensor in order to support PWM
It has three methods:
sound(power)
soundoff() -> which is the same as sound(0)
soundon() -> which is the same as sound(254), max value
'''
def __init__(self, port="D11"):
AnalogSensor.__init__(self, port, "OUTPUT")
self.set_descriptor("Buzzer")
def sound(self, power):
'''
sound takes a power argument (from 0 to 254)
the power argument will accept either a string or a numeric value
if power can't be cast to an int, then turn buzzer off
'''
try:
power = int(power)
except:
power = 0
debug(type(power))
AnalogSensor.write(self, power)
def sound_off(self):
'''
Makes buzzer silent
'''
AnalogSensor.write(self, 0)
def sound_on(self):
'''
Maximum buzzer sound
'''
AnalogSensor.write(self, 254)
##########################
class Led(AnalogSensor):
def __init__(self, port="D11"):
AnalogSensor.__init__(self, port, "OUTPUT")
self.set_descriptor("LED")
def light_on(self, power):
AnalogSensor.write(self, power)
self.value = power
def light_off(self):
AnalogSensor.write(self, 0)
def is_on(self):
return (self.value > 0)
def is_off(self):
return (self.value == 0)
##########################
class MotionSensor(DigitalSensor):
def __init__(self, port="D11"):
DigitalSensor.__init__(self, port, "INPUT")
self.set_descriptor("Motion Sensor")
##########################
class ButtonSensor(DigitalSensor):
def __init__(self, port="D11"):
DigitalSensor.__init__(self, port, "INPUT")
self.set_descriptor("Button sensor")
##########################
class Remote(Sensor):
def __init__(self, port):
global IR_RECEIVER_ENABLED
if ir_receiver_check.check_ir() == 0:
print("*** Error with the Remote Controller")
print("Please enable the IR Receiver in the Advanced Comms tool")
IR_RECEIVER_ENABLED = False
else:
Sensor.__init__(self, port, "SERIAL")
self.set_descriptor("Remote Control")
def is_enabled(self):
return IR_RECEIVER_ENABLED
def get_remote_code(self):
'''
Returns the keycode from the remote control
No preprocessing
You have to check that length > 0
before handling the code value
if the IR Receiver is not enabled, this will return -1
'''
if IR_RECEIVER_ENABLED:
return ir_receiver.nextcode()
else:
print("Error with the Remote Controller")
print("Please enable the IR Receiver in the Advanced Comms tool")
return -1
##########################
class LineFollower(Sensor):
'''
The line follower detects the presence of a black line or its
absence.
You can use this in one of three ways.
1. You can use read_position() to get a simple position status:
center, left or right.
these indicate the position of the black line.
So if it says left, the GoPiGo has to turn right
2. You can use read() to get a list of the five sensors.
each position in the list will either be a 0 or a 1
It is up to you to determine where the black line is.
3. You can use read_raw_sensors() to get raw values from all sensors
You will have to handle the calibration yourself
'''
def __init__(self, port):
Sensor.__init__(self, port, "I2C")
self.set_descriptor("Line Follower")
def read_raw_sensors(self):
'''
Returns raw values from all sensors
From 0 to 1023
May return a list of -1 when there's a read error
'''
five_vals = line_sensor.read_sensor()
if five_vals != -1:
return five_vals
else:
return [-1, -1, -1, -1, -1]
def read(self):
'''
Returns a list of 5 values between 0 and 1
Depends on the line sensor being calibrated first
through the Line Sensor Calibration tool
May return all -1 on a read error
'''
five_vals = scratch_line.absolute_line_pos()
return five_vals
def read_position(self):
'''
Returns a string telling where the black line is, compared to
the GoPiGo
Returns: "Left", "Right", "Center", "Black", "White"
May return "Unknown"
This method is not intelligent enough to handle intersections.
'''
five_vals = self.read()
if five_vals == [0, 0, 1, 0, 0] or five_vals == [0, 1, 1, 1, 0]:
return "Center"
if five_vals == [1, 1, 1, 1, 1]:
return "Black"
if five_vals == [0, 0, 0, 0, 0]:
return "White"
if five_vals == [0, 1, 1, 0, 0] or \
five_vals == [0, 1, 0, 0, 0] or \
five_vals == [1, 0, 0, 0, 0] or \
five_vals == [1, 1, 0, 0, 0] or \
five_vals == [1, 1, 1, 0, 0] or \
five_vals == [1, 1, 1, 1, 0]:
return "Left"
if five_vals == [0, 0, 0, 1, 0] or \
five_vals == [0, 0, 1, 1, 0] or \
five_vals == [0, 0, 0, 0, 1] or \
five_vals == [0, 0, 0, 1, 1] or \
five_vals == [0, 0, 1, 1, 1] or \
five_vals == [0, 1, 1, 1, 1]:
return "Right"
return "Unknown"
if __name__ == '__main__':
import time
b = Buzzer()
print (b)
print ("Sounding buzzer")
b.sound_on()
time.sleep(1)
print ("buzzer off")
b.sound_off()