From 8184387989f5cdd03623c705d99542f0e14004e4 Mon Sep 17 00:00:00 2001 From: ipa-fxm <felix.messmer@ipa.fhg.de> Date: Wed, 23 Apr 2014 13:58:12 +0200 Subject: [PATCH] some fixes --- ur_driver/prog | 2 +- ur_driver/src/ur_driver/driver.py | 7 +++---- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/ur_driver/prog b/ur_driver/prog index 420fcaa..a21a01f 100644 --- a/ur_driver/prog +++ b/ur_driver/prog @@ -1,6 +1,6 @@ def driverProg(): HOSTNAME = "%(driver_hostname)s" - PORT = driver_reverseport + PORT = %(driver_reverseport)d MSG_OUT = 1 MSG_QUIT = 2 MSG_JOINT_STATES = 3 diff --git a/ur_driver/src/ur_driver/driver.py b/ur_driver/src/ur_driver/driver.py index 6c6caa6..bf52483 100755 --- a/ur_driver/src/ur_driver/driver.py +++ b/ur_driver/src/ur_driver/driver.py @@ -668,7 +668,7 @@ def main(): (options, args) = parser.parse_args(rospy.myargv()[1:]) if len(args) < 1: parser.error("You must specify the robot hostname") - elif len(args == 1: + elif len(args) == 1: robot_hostname = args[0] reverse_port = REVERSE_PORT elif len(args) == 2: @@ -687,14 +687,13 @@ def main(): max_velocity = rospy.get_param("~max_velocity", 2.0) # Sets up the server for the robot to connect to - server = TCPServer(("", REVERSE_PORT), CommanderTCPHandler) + server = TCPServer(("", reverse_port), CommanderTCPHandler) thread_commander = threading.Thread(name="CommanderHandler", target=server.serve_forever) thread_commander.daemon = True thread_commander.start() with open(roslib.packages.get_pkg_dir('ur_driver') + '/prog') as fin: - program = fin.read() % {"driver_hostname": get_my_ip(robot_hostname, reverse_port)} - program = fin.read() % {"driver_reverseport": reverse_port} + program = fin.read() % {"driver_hostname": get_my_ip(robot_hostname, reverse_port), "driver_reverseport": reverse_port} connection = URConnection(robot_hostname, PORT, program) connection.connect() connection.send_reset_program() -- GitLab