8 FUN_SET_DIGITAL_OUT = 1
10 FUN_SET_ANALOG_OUT = 3
11 FUN_SET_TOOL_VOLTAGE = 4
14 Digital_Out_States = [0,0,0,0,0,0,0,0,0,0]
15 Digital_In_States = [0,0,0,0,0,0,0,0,0,0]
16 Analog_Out_States = [0,0]
17 Analog_In_States = [0,0]
19 ANALOG_TOLERANCE_VALUE = 0.01
24 except rospy.ServiceException
as e:
25 print "Service call failed: %s"%e
29 set_io(FUN_SET_TOOL_VOLTAGE, volts, 0)
30 except rospy.ServiceException
as e:
31 print "Service call failed: %s"%e
35 set_io(FUN_SET_DIGITAL_OUT, pin, val)
36 except rospy.ServiceException
as e:
37 print "Service call failed: %s"%e
41 set_io(FUN_SET_ANALOG_OUT, pin, val)
42 except rospy.ServiceException
as e:
43 print "Service call failed: %s"%e
46 rospy.logerr(
"SETTING FLAGS IS NOT SUPPORTED!")
53 rospy.logerr(
"Flag_States are currently not supported")
58 del Digital_Out_States[i]
59 Digital_Out_States.insert(i, data.digital_out_states[i].state)
61 del Digital_In_States[i]
62 Digital_In_States.insert(i, data.digital_in_states[i].state)
64 del Analog_Out_States[i]
65 Analog_Out_States.insert(i, data.analog_out_states[i].state)
66 rospy.logerr(
"ToolInput analog_in[2] and analog_in[3] currently not supported")
68 del Analog_In_States[i]
69 Analog_In_States.insert(i, data.analog_in_states[i].state)
72 rospy.init_node(
'UR_State_Getter')
73 rospy.Subscriber(
"io_states", IOStates, callback)
76 rospy.wait_for_service(
'set_io')
78 set_io = rospy.ServiceProxy(
'set_io', SetIO)
def set_digital_out(pin, val)
def set_tool_voltage(volts)
def set_analog_out(pin, val)
def set_io_val(fun, pin, val)