diff --git a/ur_driver/prog b/ur_driver/prog index 2f0aff8c1b30d442bf8c30d64f237887e7efbf5a..58f680e39acf44ec98fb366f4651986c0640947c 100644 --- a/ur_driver/prog +++ b/ur_driver/prog @@ -20,6 +20,7 @@ def driverProg(): MULT_jointstate = 10000.0 MULT_time = 1000000.0 MULT_blend = 1000.0 + MULT_analog = 1000000.0 pi = 3.14159265359 def send_out(msg): @@ -73,13 +74,13 @@ def driverProg(): socket_send_int(MSG_GET_IO) socket_send_int(1*get_digital_in(0) + 2*get_digital_in(1) + 4 * get_digital_in(2) + 8 * get_digital_in(3) + 16 * get_digital_in(4) + 32 * get_digital_in(5) + 64 * get_digital_in(6) + 128 * get_digital_in(7) + 256 * get_digital_in(8) + 512 * get_digital_in(9)) socket_send_int(1*get_digital_out(0) + 2*get_digital_out(1) + 4 * get_digital_out(2) + 8 * get_digital_out(3) + 16 * get_digital_out(4) + 32 * get_digital_out(5) + 64 * get_digital_out(6) + 128 * get_digital_out(7) + 256 * get_digital_out(8) + 512 * get_digital_out(9)) - socket_send_int(pow(2,0)*get_flag(0) + pow(2,1)*get_flag(1) + pow(2,2)*get_flag(2) + pow(2,3)*get_flag(3) + pow(2,4)*get_flag(4) + pow(2,5)*get_flag(5) + pow(2,6)*get_flag(6) + pow(2,7)*get_flag(7) + pow(2,8)*get_flag(8) + pow(2,9)*get_flag(9) + pow(2,10)*get_flag(10) + pow(2,11)*get_flag(11) + pow(2,12)*get_flag(12) + pow(2,13)*get_flag(13) + pow(2,14)*get_flag(14) + pow(2,15)*get_flag(15) + pow(2,16)*get_flag(16) + pow(2,17)*get_flag(17) + pow(2,18)*get_flag(18) + pow(2,19)*get_flag(19) + pow(2,20)*get_flag(20) + pow(2,21)*get_flag(21) + pow(2,22)*get_flag(22) + pow(2,23)*get_flag(23) + pow(2,24)*get_flag(24) + pow(2,25)*get_flag(25) + pow(2,26)*get_flag(26) + pow(2,27)*get_flag(27) + pow(2,28)*get_flag(28) + pow(2,29)*get_flag(29) + pow(2,30)*get_flag(30) + pow(2,31)*get_flag(31)) - socket_send_int(get_analog_out(0)*1000000) - socket_send_int(get_analog_out(1)*1000000) - socket_send_int(get_analog_in(0)*1000000) - socket_send_int(get_analog_in(1)*1000000) - socket_send_int(get_analog_in(2)*1000000) - socket_send_int(get_analog_in(3)*1000000) + socket_send_int(pow(2,0)*get_flag(0) + pow(2,1)*get_flag(1) + pow(2,2)*get_flag(2) + pow(2,3)*get_flag(3) + pow(2,4)*get_flag(4) + pow(2,5)*get_flag(5) + pow(2,6)*get_flag(6) + pow(2,7)*get_flag(7) + pow(2,8)*get_flag(8) + pow(2,9)*get_flag(9) + pow(2,10)*get_flag(10) + pow(2,11)*get_flag(11) + pow(2,12)*get_flag(12) + pow(2,13)*get_flag(13) + pow(2,14)*get_flag(14) + pow(2,15)*get_flag(15) + pow(2,16)*get_flag(16) + pow(2,17)*get_flag(17) + pow(2,18)*get_flag(18) + pow(2,19)*get_flag(19) + pow(2,20)*get_flag(20) + pow(2,21)*get_flag(21) + pow(2,22)*get_flag(22) + pow(2,23)*get_flag(23) + pow(2,24)*get_flag(24) + pow(2,25)*get_flag(25) + pow(2,26)*get_flag(26) + pow(2,27)*get_flag(27) + pow(2,28)*get_flag(28) + pow(2,29)*get_flag(29) + pow(2,30)*get_flag(30) + pow(2,31)*get_flag(31) + pow(2,32)*get_flag(32)) + socket_send_int(get_analog_out(0) * MULT_analog) + socket_send_int(get_analog_out(1) * MULT_analog) + socket_send_int(get_analog_in(0) * MULT_analog) + socket_send_int(get_analog_in(1) * MULT_analog) + socket_send_int(get_analog_in(2) * MULT_analog) + socket_send_int(get_analog_in(3) * MULT_analog) #socket_send_int(7895160) # Recognizable ".xxx" or 00787878 exit_critical end @@ -263,7 +264,7 @@ def driverProg(): if params_mult[0] == 0: send_out("Received no parameters for set_out message") end - set_analog_out(params_mult[1], (params_mult[2] / 1000000)) + set_analog_out(params_mult[1], (params_mult[2] / MULT_analog)) elif mtype == MSG_SET_TOOL_VOLTAGE: #send_out("Received Tool Voltage Signal") # Reads the parameters diff --git a/ur_driver/src/ur_driver/driver.py b/ur_driver/src/ur_driver/driver.py index 007295374b34f988d2e465781f84a69fb077752c..dcb28bdeda1537effc98d8e5ad311e5f1fe8b15f 100755 --- a/ur_driver/src/ur_driver/driver.py +++ b/ur_driver/src/ur_driver/driver.py @@ -57,6 +57,7 @@ MULT_wrench = 10000.0 MULT_jointstate = 10000.0 MULT_time = 1000000.0 MULT_blend = 1000.0 +MULT_analog = 1000000.0 #Bounds for SetPayload service MIN_PAYLOAD = 0.0 @@ -378,42 +379,42 @@ class CommanderTCPHandler(SocketServer.BaseRequestHandler): while len(buf) < 4: buf = buf + self.recv_more() inp = struct.unpack_from("!i", buf, 0)[0] - inp /= 1000000.0 + inp /= MULT_analog buf = buf[4:] msg.analog_out_states.append(Analog(0, inp)) #gets analog_out[1] state while len(buf) < 4: buf = buf + self.recv_more() inp = struct.unpack_from("!i", buf, 0)[0] - inp /= 1000000.0 + inp /= MULT_analog buf = buf[4:] msg.analog_out_states.append(Analog(1, inp)) #gets analog_in[0] state while len(buf) < 4: buf = buf + self.recv_more() inp = struct.unpack_from("!i", buf, 0)[0] - inp /= 1000000.0 + inp /= MULT_analog buf = buf[4:] msg.analog_in_states.append(Analog(0, inp)) #gets analog_in[1] state while len(buf) < 4: buf = buf + self.recv_more() inp = struct.unpack_from("!i", buf, 0)[0] - inp /= 1000000.0 + inp /= MULT_analog buf = buf[4:] msg.analog_in_states.append(Analog(1, inp)) #gets analog_in[2] state while len(buf) < 4: buf = buf + self.recv_more() inp = struct.unpack_from("!i", buf, 0)[0] - inp /= 1000000.0 + inp /= MULT_analog buf = buf[4:] msg.analog_in_states.append(Analog(2, inp)) #gets analog_in[3] state while len(buf) < 4: buf = buf + self.recv_more() inp = struct.unpack_from("!i", buf, 0)[0] - inp /= 1000000.0 + inp /= MULT_analog buf = buf[4:] msg.analog_in_states.append(Analog(3, inp)) pub_io_states.publish(msg) @@ -472,7 +473,7 @@ class CommanderTCPHandler(SocketServer.BaseRequestHandler): def set_analog_out(self, pinnum, value): params = [MSG_SET_ANALOG_OUT] + \ [pinnum] + \ - [value * 1000000] + [value * MULT_analog] buf = struct.pack("!%ii" % len(params), *params) #print params with self.socket_lock: