diff --git a/ur_driver/src/ur_driver/driver.py b/ur_driver/src/ur_driver/driver.py index 0245191366a40d9178f01216d135c28d896949ed..aa5c440eaa8f56cf467294f34a45c51987f5b9a5 100755 --- a/ur_driver/src/ur_driver/driver.py +++ b/ur_driver/src/ur_driver/driver.py @@ -459,7 +459,7 @@ class CommanderTCPHandler(SocketServer.BaseRequestHandler): if not buf: buf = buf + self.recv_more() - except EOF, ex: + except EOF as ex: print("Connection closed (command):", ex) setConnectedRobot(None) @@ -964,7 +964,7 @@ def main(): prevent_programming = rospy.get_param("~prevent_programming") update = {'prevent_programming': prevent_programming} reconfigure_srv.update_configuration(update) - except KeyError, ex: + except KeyError as ex: print("Parameter 'prevent_programming' not set. Value: " + str(prevent_programming)) pass if prevent_programming: @@ -985,7 +985,7 @@ def main(): prevent_programming = rospy.get_param("~prevent_programming") update = {'prevent_programming': prevent_programming} reconfigure_srv.update_configuration(update) - except KeyError, ex: + except KeyError as ex: print("Parameter 'prevent_programming' not set. Value: " + str(prevent_programming)) pass connection.send_program() diff --git a/ur_driver/src/ur_driver/io_interface.py b/ur_driver/src/ur_driver/io_interface.py index e78c0b4236aae3c773debffabf4db4ce96e2eb4c..882a7ce7afa3454324563e312b054d11abb2ba4f 100644 --- a/ur_driver/src/ur_driver/io_interface.py +++ b/ur_driver/src/ur_driver/io_interface.py @@ -21,25 +21,25 @@ ANALOG_TOLERANCE_VALUE = 0.01 def set_io_val(fun, pin, val): try: set_io(fun, pin, val) - except rospy.ServiceException, e: + except rospy.ServiceException as e: print "Service call failed: %s"%e def set_tool_voltage(volts): try: set_io(FUN_SET_TOOL_VOLTAGE, volts, 0) - except rospy.ServiceException, e: + except rospy.ServiceException as e: print "Service call failed: %s"%e def set_digital_out(pin, val): try: set_io(FUN_SET_DIGITAL_OUT, pin, val) - except rospy.ServiceException, e: + except rospy.ServiceException as e: print "Service call failed: %s"%e def set_analog_out(pin, val): try: set_io(FUN_SET_ANALOG_OUT, pin, val) - except rospy.ServiceException, e: + except rospy.ServiceException as e: print "Service call failed: %s"%e def set_flag(pin, val):