Skip to content
Snippets Groups Projects
Commit c54fd389 authored by ipa-fxm's avatar ipa-fxm
Browse files

disable flags in io_interface and test_io

parent a8f1cebf
Branches
Tags
No related merge requests found
...@@ -116,18 +116,9 @@ def driverProg(): ...@@ -116,18 +116,9 @@ def driverProg():
exit_critical exit_critical
end end
#temporarily reduce publish rate for io_states
io_count = 0
io_slowdown_ratio = 10
send_io_state() send_io_state()
while True: while True:
if io_count != io_slowdown_ratio: send_io_state()
io_count=io_count+1
else:
send_io_state()
io_count=0
end
sync() sync()
end end
sync() sync()
......
...@@ -50,9 +50,9 @@ def set_flag(pin, val): ...@@ -50,9 +50,9 @@ def set_flag(pin, val):
set_digital_out(pin, val) set_digital_out(pin, val)
def callback(data): def callback(data):
for i in range(0,32): #for i in range(0,32):
del Flag_States[i] #del Flag_States[i]
Flag_States.insert(i, data.flag_states[i].state) #Flag_States.insert(i, data.flag_states[i].state)
for i in range(0,10): for i in range(0,10):
del Digital_Out_States[i] del Digital_Out_States[i]
Digital_Out_States.insert(i, data.digital_out_states[i].state) Digital_Out_States.insert(i, data.digital_out_states[i].state)
......
...@@ -10,16 +10,18 @@ if __name__ == "__main__": ...@@ -10,16 +10,18 @@ if __name__ == "__main__":
set_tool_voltage(12) set_tool_voltage(12)
set_digital_out(0, True) set_digital_out(0, True)
set_analog_out(0, 0.75) set_analog_out(0, 0.75)
set_flag(0, True) print "Flags are currently not supported"
print(Flag_States[0]) #set_flag(0, True)
#print(Flag_States[0])
print(Analog_Out_States[0]) print(Analog_Out_States[0])
print(Digital_Out_States[0]) print(Digital_Out_States[0])
time.sleep(1) time.sleep(1)
set_tool_voltage(24) set_tool_voltage(24)
set_digital_out(0, False) set_digital_out(0, False)
set_analog_out(0, 0.25) set_analog_out(0, 0.25)
set_flag(0, False) print "Flags are currently not supported"
print(Flag_States[0]) #set_flag(0, False)
#print(Flag_States[0])
print(Analog_Out_States[0]) print(Analog_Out_States[0])
print(Digital_Out_States[0]) print(Digital_Out_States[0])
time.sleep(1) time.sleep(1)
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment