Skip to content
Snippets Groups Projects
Commit 88b39781 authored by 42loop's avatar 42loop
Browse files

migrated dotserver.py to real bus access

parent b160177f
No related branches found
No related tags found
No related merge requests found
......@@ -20,6 +20,8 @@ if platform!="":
data0=0
data1=0
data2=0xaa
last_sensors=0
sensors=0
......@@ -33,10 +35,33 @@ laststate=st_stop
pwm_left=12
pwm_right=33
#d0 - d7
data_pins=[7,8,10,11,13,15,16,18]
data_dir=22
data_gate=40
data_out=GPIO.HIGH
data_in=GPIO.LOW
data_en=GPIO.LOW
data_dis=GPIO.HIGH
a0=29
a1=31
a2=32
a3=35
a4=36
rd=37
wr=38
#master card number:
master_out=2
data_strobe0=22
data_strobe1=40
extra_out=3
master_in=4
data0_ids={"fwd":0,"bwd":1,"LL":2,"LR":3,"RL":4,"RR":5,"none":6,"none":7}
data1_ids={"lbrushcw":0,"lbrushccw":1,"rbrushcw":2,"rbrushccw":3,"col1":4,"col2":5,"col3":6,"col4":7}
......@@ -45,7 +70,7 @@ data1_ids={"lbrushcw":0,"lbrushccw":1,"rbrushcw":2,"rbrushccw":3,"col1":4,"col2"
##### id_sd 27
##### id_sc 28
estop_pins=[29,31,32,35,36,37,38]
#estop_pins=[29,31,32,35,36,37,38]
sensor_ids=["railstart","railend","railposition","left","right","center","none"]
......@@ -113,40 +138,166 @@ pumptargets=[
#################################################
def blink(pin):
GPIO.output(pin,GPIO.HIGH)
time.sleep(.01)
GPIO.output(pin,GPIO.LOW)
time.sleep(.01)
def set_adr_pins(adr):
if ((adr>>0)&1==1):
GPIO.output(a0,GPIO.HIGH)
else:
GPIO.output(a0,GPIO.LOW)
if ((adr>>1)&1==1):
GPIO.output(a1,GPIO.HIGH)
else:
GPIO.output(a1,GPIO.LOW)
def set_card_adr(card):
if ((card>>0)&1==1):
GPIO.output(a2,GPIO.HIGH)
else:
GPIO.output(a2,GPIO.LOW)
if ((card>>1)&1==1):
GPIO.output(a3,GPIO.HIGH)
else:
GPIO.output(a3,GPIO.LOW)
#####################################################
if ((card>>2)&1==1):
GPIO.output(a4,GPIO.HIGH)
else:
GPIO.output(a4,GPIO.LOW)
def init_hardware():
if platform!="":
print("setting up GPIO")
print("setup data_strobe0:",data_strobe0)
def set_data_pins(d):
#print("data0: ",data0)
for b in range(0,8):
if ((d>>b)&1==1):
GPIO.output(data_pins[b],GPIO.HIGH)
else:
GPIO.output(data_pins[b],GPIO.LOW)
def get_data_pins():
#print("data0: ",data0)
v=0
t_data=0
for b in range(0,7):
v=GPIO.input(data_pins[b])
if (v==1):
t_data=t_data | (1<<b)
return t_data
def strobe_wr():
GPIO.output(wr,GPIO.LOW)
time.sleep(.001)
GPIO.output(wr,GPIO.HIGH)
def strobe_rd():
GPIO.output(rd,GPIO.LOW)
time.sleep(.001)
GPIO.output(rd,GPIO.HIGH)
def write_data(card_no,adr,d):
#print("WRITE card_no: ",card_no," subadr: ",adr," data: ",d)
set_data_out()
GPIO.output(data_dir,data_out)
#time.sleep(0.001)
set_data_pins(d)
#time.sleep(0.001)
GPIO.output(data_gate,data_en)
#time.sleep(0.001)
set_adr_pins(adr)
set_card_adr(card_no)
time.sleep(0.01)
strobe_wr()
time.sleep(0.01)
GPIO.output(data_gate,data_dis)
set_data_pins(0)
set_adr_pins(15)
#time.sleep(0.01)
def read_data(card_no,adr):
set_data_in()
GPIO.output(data_dir,data_in)
set_adr_pins(adr)
set_card_adr(card_no)
GPIO.output(data_gate,data_en)
time.sleep(0.01)
strobe_rd()
time.sleep(0.01)
result=get_data_pins()
GPIO.setup(data_strobe0,GPIO.OUT)
GPIO.output(data_strobe0,GPIO.LOW)
GPIO.output(data_gate,data_dis)
set_data_out()
set_data_pins(0)
set_adr_pins(15)
print("setup data_strobe1:",data_strobe1)
GPIO.setup(data_strobe1,GPIO.OUT)
GPIO.output(data_strobe1,GPIO.LOW)
#print("READ card_no: ",card_no," subadr: ",adr," data: ",result)
print("setup data pins")
return result
def set_data_out():
#print("setup data pins out")
for i in range(0,8):
print("pin: ",data_pins[i])
# print("pin: ",data_pins[i])
GPIO.setup(data_pins[i],GPIO.OUT)
GPIO.output(data_pins[i],GPIO.LOW)
print("setup estop pins:")
for i in range(0,7):
print("pin: ",estop_pins[i])
try:
GPIO.setup(estop_pins[i],GPIO.IN,pull_up_down=GPIO.PUD_DOWN)
except:
print(estop_pins[i],"trouble")
pass
#GPIO.output(estop_pins[i],GPIO.LOW)
def set_data_in():
#print("setup data pins in")
for i in range(0,8):
# print("pin: ",data_pins[i])
GPIO.setup(data_pins[i],GPIO.IN)
#####################################################
def init_hardware():
#if platform!="":
print("setting up GPIO")
print("setup data_dir:",data_dir)
GPIO.setup(data_dir,GPIO.OUT)
GPIO.output(data_dir,data_out)
print("setup data_gate:",data_gate)
GPIO.setup(data_gate,GPIO.OUT)
GPIO.output(data_gate,data_dis)
set_data_out()
print("setup address pins:")
GPIO.setup(a0,GPIO.OUT)
GPIO.setup(a1,GPIO.OUT)
GPIO.setup(a2,GPIO.OUT)
GPIO.setup(a3,GPIO.OUT)
GPIO.setup(a4,GPIO.OUT)
GPIO.output(a0,GPIO.LOW)
GPIO.output(a1,GPIO.LOW)
GPIO.output(a2,GPIO.LOW)
GPIO.output(a3,GPIO.LOW)
GPIO.output(a4,GPIO.LOW)
print("setup read/write pins:")
GPIO.setup(rd,GPIO.OUT)
GPIO.setup(wr,GPIO.OUT)
GPIO.output(rd,GPIO.HIGH)
GPIO.output(rd,GPIO.HIGH)
print("init spi channel for adc")
spi_max_speed = 10000 # 4 MHz
......@@ -170,44 +321,10 @@ def init_hardware():
print("hardware setup done")
###################################################
def get_sensors():
global sensors
t_estops=0
for b in range(0,7):
v=GPIO.input(estop_pins[b])
if (v==1):
t_estops=t_estops | (1<<b)
sensors=t_estops
#################################################
###################################################
def set_data():
#print("data0: ",data0)
for b in range(0,8):
if ((data0>>b)&1==1):
GPIO.output(data_pins[b],GPIO.HIGH)
else:
GPIO.output(data_pins[b],GPIO.LOW)
GPIO.output(data_strobe0,GPIO.HIGH)
time.sleep(.01)
GPIO.output(data_strobe0,GPIO.LOW)
#print("data1: ",data1)
for b in range(0,8):
if ((data1>>b)&1==1):
GPIO.output(data_pins[b],GPIO.HIGH)
else:
GPIO.output(data_pins[b],GPIO.LOW)
GPIO.output(data_strobe1,GPIO.HIGH)
time.sleep(.01)
GPIO.output(data_strobe1,GPIO.LOW)
###################################################
def initsequences():
......@@ -270,7 +387,7 @@ def forward_on():
# print(data0_ids["fwd"])
data0=data0 | 1<<data0_ids["fwd"]
set_data()
# write_data(master_out,0,data0)
state=st_fwd
if state!=laststate:
......@@ -285,8 +402,8 @@ def backward_on():
global data0
# print(data0_ids["fwd"])
data0=data0 | 1<<data0_ids["fwd"]
set_data()
data0=data0 | 1<<data0_ids["bwd"]
# write_data(master_out,0,data0)
state=st_bwd
if state!=laststate:
......@@ -302,7 +419,7 @@ def stop():
data0=data0 & ~(1<<data0_ids["fwd"])
data0=data0 & ~(1<<data0_ids["bwd"])
set_data()
# write_data(master_out,0,data0)
#GPIO.output(bwd_pin,GPIO.LOW)
#GPIO.output(fwd_pin,GPIO.LOW)
......@@ -322,11 +439,13 @@ def quicktimerevent():
global power
global last_sensors
get_sensors()
sensors=read_data(master_in,0)
if sensors!=last_sensors:
print(sensors)
last_sensors=sensors
if stoprequested:
if (actual_left_speed==0) and (actual_right_speed==0) and (actual_track_speed==0):
power=False
......@@ -352,6 +471,11 @@ def quicktimerevent():
actual_track_speed-=1
setMoveOutput(actual_track_speed)
write_data(master_out,0,data0)
write_data(master_out,1,data1)
write_data(extra_out,0,data2)
sendStatus()
......@@ -373,6 +497,16 @@ def sectimerevent():
global nextpumptarget
global stoprequested
global data2
data2=random.randint(0,255)
return
time_elap+=1
if power:
......@@ -520,7 +654,8 @@ def setRotateOutput(id, speed):
pwmright.ChangeDutyCycle(abs(speed))
set_data()
# write_data(master_out,1,data1)
###################################################
......@@ -531,6 +666,20 @@ def connected():
########################################################
def disconnected():
global data1
print("DISCONNECTED")
data1=data1 & ~(1<<data1_ids["col1"])
data1=data1 & ~(1<<data1_ids["col2"])
data1=data1 & ~(1<<data1_ids["col3"])
data1=data1 & ~(1<<data1_ids["col4"])
########################################################
#clicked event
def pressed(pos,id):
......@@ -592,12 +741,13 @@ def pressed(pos,id):
elif id in data0_ids:
if power:
data0=data0 | 1<<data0_ids[id]
set_data()
# write_data(master_out,0,data0)
elif id in data1_ids:
if power:
data1=data1 | 1<<data1_ids[id]
set_data()
# write_data(master_out,1,data1)
######################################################
......@@ -633,12 +783,13 @@ def released(pos,id):
elif id in data0_ids:
#print(data0_ids[id])
data0=data0 & ~(1<<data0_ids[id])
set_data()
# write_data(master_out,0,data0)
elif id in data1_ids:
#print(data1_ids[id])
data1=data1 & ~(1<<data1_ids[id])
set_data()
# write_data(master_out,1,data1)
......@@ -701,7 +852,8 @@ pwmright = GPIO.PWM(pwm_right, 100) # Initialize PWM on pwmPin 100Hz frequency
init_hardware()
set_data()
write_data(master_out,0,data0)
write_data(master_out,1,data1)
#initsequences()
......@@ -725,7 +877,7 @@ target_speed=0
t = aTimer(1,sectimerevent)
#t.start()
t.start()
t2 = aTimer(.1,quicktimerevent)
t2.start()
......@@ -736,6 +888,7 @@ bd.when_rotated = rotated
bd.when_pressed = pressed
bd.when_released = released
bd.when_client_connects = connected
bd.when_client_disconnects = disconnected
pause()
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment