Skip to content

Commit 8a2ec0f

Browse files
authored
Line follower (DexterInd#276)
* Attempt at making easygopigo thread_safe First, before each read, wait till the bus is available Second, confirm the bus is open before doing the read (in case another thread got it) Third, grab the read flag Fourth do the read Fifth, release the read flag asap for other threads This only works for one process and only if all readings go through easygopigo More than one process would still experience issues, but a single multi threaded process would be safe. * Install line follower in a standard way. To import use: from line_follower import line_sensor and it works! * get rid of double self. One ego is enough * Some phantom lines had reappeared. I must have goofed in Github again * Change the way the IR Receiver behaves on GPG2. By default, the behaviour is the same as before, but now we can have a "consume" stauts. When 'consume' is set to False, the key is not erased and can be returned more than once. * remove extra blank line * Limit percent readings to 100. Mostly for sound and loudness sensors. We don't want to encourage classrooms into noise contests * feature - assembly instructions for the GoPiGo2 (DexterInd#274) feature - assembly instructions for the GoPiGo2 * Make the line follower returns all lowercase letters. Easier for string manipulation Needed for DexterOS * _is_read_open() is obsolete
1 parent 959ff46 commit 8a2ec0f

File tree

3 files changed

+53
-49
lines changed

3 files changed

+53
-49
lines changed

Software/Python/easygopigo.py

100755100644
Lines changed: 47 additions & 48 deletions
Original file line numberDiff line numberDiff line change
@@ -73,7 +73,7 @@ def _release_read():
7373
pass
7474
read_is_open = True
7575
# print("released")
76-
76+
7777

7878
class EasyGoPiGo():
7979
'''
@@ -83,12 +83,12 @@ class EasyGoPiGo():
8383
'''
8484
def __init__(self):
8585
'''
86-
On Init, set speed to half-way, so GoPiGo is predictable
86+
On Init, set speed to half-way, so GoPiGo is predictable
8787
and not too fast.
8888
'''
8989
DEFAULT_SPEED = 128
9090
gopigo.set_speed(DEFAULT_SPEED)
91-
91+
9292
def volt(self):
9393
_grab_read()
9494
try:
@@ -122,13 +122,13 @@ def backward(self):
122122
print("easygopigo bwd: {}".format(e))
123123
pass
124124
_release_read()
125-
125+
126126
def left(self):
127127
_grab_read()
128128
try:
129129
gopigo.left()
130130
except:
131-
pass
131+
pass
132132
_release_read()
133133

134134
def right(self):
@@ -146,15 +146,15 @@ def set_speed(self,new_speed):
146146
except:
147147
pass
148148
_release_read()
149-
149+
150150
def reset_speed(self):
151151
_grab_read()
152152
try:
153153
gopigo.set_speed(DEFAULT_SPEED)
154154
except:
155155
pass
156-
_release_read()
157-
156+
_release_read()
157+
158158
def set_left_speed(self,new_speed):
159159
_grab_read()
160160
try:
@@ -170,32 +170,32 @@ def set_right_speed(self,new_speed):
170170
except:
171171
pass
172172
_release_read()
173-
173+
174174
def led_on(self,led_id):
175175
_grab_read()
176176
try:
177177
gopigo.led_on(led_id)
178178
except:
179179
pass
180180
_release_read()
181-
181+
182182
def led_off(self,led_id):
183183
_grab_read()
184184
try:
185185
gopigo.led_off(led_id)
186186
except:
187187
pass
188188
_release_read()
189-
189+
190190
def trim_read(self):
191191
_grab_read()
192192
try:
193-
current_trim = int(gopigo.trim_read())
193+
current_trim = int(gopigo.trim_read())
194194
except:
195195
pass
196196
_release_read()
197197
return current_trim
198-
198+
199199
def trim_write(self,set_trim_to):
200200
_grab_read()
201201
try:
@@ -345,15 +345,15 @@ def read(self):
345345
try:
346346
self.value = gopigo.analogRead(self.getPortID())
347347
except:
348-
pass
348+
pass
349349
_release_read()
350350
return self.value
351351

352352
def percent_read(self):
353353
value = int(self.read()) * 100 // self._max_value
354-
355-
# limit percent_read to a max of 100%. We don't want to encourage
356-
# classrooms into shouting matches with the sound sensor
354+
# Some sensors - like the loudness_sensor -
355+
# can actually return higher than 100% so let's clip it
356+
# and keep classrooms within an acceptable noise level
357357
if value > 100:
358358
value = 100
359359
# print(value)
@@ -556,7 +556,7 @@ class ButtonSensor(DigitalSensor):
556556
def __init__(self, port="D11",gpg=None):
557557
DigitalSensor.__init__(self, port, "INPUT")
558558
self.set_descriptor("Button sensor")
559-
559+
560560
def is_button_pressed(self):
561561
return self.read() == 1
562562
##########################
@@ -588,13 +588,15 @@ def get_remote_code(self):
588588
You have to check that length > 0
589589
before handling the code value
590590
'''
591+
591592
if IR_RECEIVER_ENABLED:
592593
import ir_receiver
593594
key = ir_receiver.nextcode(consume=False)
594595
else:
595596
key = ""
596-
597+
597598
return key
599+
598600
##########################
599601

600602

@@ -695,17 +697,17 @@ def follow_line(self,fwd_speed=80):
695697
while True:
696698
pos = self.read_position()
697699
debug(pos)
698-
if pos == "Center":
700+
if pos == "center":
699701
gopigo.forward()
700-
elif pos == "Left":
702+
elif pos == "left":
701703
gopigo.set_right_speed(0)
702704
gopigo.set_left_speed(slight_turn_speed)
703-
elif pos == "Right":
705+
elif pos == "right":
704706
gopigo.set_right_speed(slight_turn_speed)
705707
gopigo.set_left_speed(0)
706-
elif pos == "Black":
708+
elif pos == "black":
707709
gopigo.stop()
708-
elif pos == "White":
710+
elif pos == "white":
709711
gopigo.stop()
710712

711713
def read_position(self):
@@ -716,32 +718,29 @@ def read_position(self):
716718
May return "Unknown"
717719
This method is not intelligent enough to handle intersections.
718720
'''
719-
five_vals = [-1,-1,-1,-1,-1]
720-
721-
if _is_read_open():
722-
five_vals = self.read()
721+
five_vals = self.read()
723722

724723
if five_vals == [0, 0, 1, 0, 0] or five_vals == [0, 1, 1, 1, 0]:
725-
return "Center"
724+
return "center"
726725
if five_vals == [1, 1, 1, 1, 1]:
727-
return "Black"
726+
return "black"
728727
if five_vals == [0, 0, 0, 0, 0]:
729-
return "White"
728+
return "white"
730729
if five_vals == [0, 1, 1, 0, 0] or \
731730
five_vals == [0, 1, 0, 0, 0] or \
732731
five_vals == [1, 0, 0, 0, 0] or \
733732
five_vals == [1, 1, 0, 0, 0] or \
734733
five_vals == [1, 1, 1, 0, 0] or \
735734
five_vals == [1, 1, 1, 1, 0]:
736-
return "Left"
735+
return "left"
737736
if five_vals == [0, 0, 0, 1, 0] or \
738737
five_vals == [0, 0, 1, 1, 0] or \
739738
five_vals == [0, 0, 0, 0, 1] or \
740739
five_vals == [0, 0, 0, 1, 1] or \
741740
five_vals == [0, 0, 1, 1, 1] or \
742741
five_vals == [0, 1, 1, 1, 1]:
743-
return "Right"
744-
return "Unknown"
742+
return "right"
743+
return "unknown"
745744

746745

747746
#######################################################################
@@ -751,23 +750,23 @@ def read_position(self):
751750
#######################################################################
752751

753752
class Servo(Sensor):
754-
753+
755754
def __init__(self, port="SERVO", gpg=None):
756755
Sensor.__init__(self, port, "SERVO")
757756
gopigo.enable_servo()
758757
self.set_descriptor("Servo Motor")
759-
758+
760759
def rotate_servo(self, servo_position):
761760
if servo_position > 180:
762761
servo_position = 180
763762
if servo_position < 0:
764763
servo_position = 0
765764
gopigo.servo(servo_position)
766-
767-
765+
766+
768767
#######################################################################
769768
#
770-
# DistanceSensor
769+
# DistanceSensor
771770
#
772771
#######################################################################
773772
try:
@@ -791,18 +790,18 @@ def __init__(self, port="I2C",gpg=None):
791790
except Exception as e:
792791
print(e)
793792
raise ValueError("Distance Sensor not found")
794-
793+
795794
# Returns the values in mm
796795
readings = []
797796
def read_mm(self):
798-
797+
799798
# 8190 is what the sensor sends when it's out of range
800799
# we're just setting a default value
801800
mm = 8190
802801
readings = []
803802
attempt = 0
804-
805-
# try 3 times to have a reading that is
803+
804+
# try 3 times to have a reading that is
806805
# smaller than 8m or bigger than 5 mm.
807806
# if sensor insists on that value, then pass it on
808807
while (mm > 8000 or mm < 5) and attempt < 3:
@@ -814,26 +813,26 @@ def read_mm(self):
814813
_release_read()
815814
attempt = attempt + 1
816815
time.sleep(0.001)
817-
816+
818817
# add the reading to our last 3 readings
819818
# a 0 value is possible when sensor is not found
820819
if (mm < 8000 and mm > 5) or mm == 0:
821820
readings.append(mm)
822821
if len(readings) > 3:
823822
readings.pop(0)
824-
823+
825824
# calculate an average and limit it to 5 > X > 3000
826825
if len(readings) > 1: # avoid division by 0
827826
mm = round(sum(readings) / float(len(readings)))
828827
if mm > 3000:
829828
mm = 3000
830-
829+
831830
return mm
832-
831+
833832
def read(self):
834833
cm = self.read_mm()//10
835834
return (cm)
836-
835+
837836
def read_inches(self):
838837
cm = self.read()
839838
return cm / 2.54

Software/Python/ir_remote_control/server/ir_receiver.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -61,6 +61,7 @@ def nextcode(consume=True):
6161
global previous_keypress
6262

6363
send_back=last_recv_or_code
64+
6465
# print("send_back: {} previous_keypress: {}".format(send_back,previous_keypress))
6566

6667
if consume:

Software/Python/line_follower/line_sensor.py

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -124,8 +124,12 @@ def read_sensor():
124124
try:
125125
output_values = []
126126
bus.write_i2c_block_data(address, 1, aRead_cmd + [unused, unused, unused])
127+
128+
# for some unknown reason we need to discard the first reading
129+
# otherwise we're not up to date
127130
number = bus.read_i2c_block_data(address, 1)
128-
131+
number = bus.read_i2c_block_data(address, 1)
132+
129133
# for each IR sensor on the line follower
130134
for i in range(5):
131135
# calculate the 2-byte number we got

0 commit comments

Comments
 (0)