From 1996a821027980f4456a746fd7cfa1f8f298e371 Mon Sep 17 00:00:00 2001
From: Stuart Glaser <sglaser@willowgarage.com>
Date: Thu, 29 Mar 2012 16:23:43 -0700
Subject: [PATCH] Parses the robot hostname from the command line

---
 ur5_driver/driver.py | 12 +++++++++---
 1 file changed, 9 insertions(+), 3 deletions(-)

diff --git a/ur5_driver/driver.py b/ur5_driver/driver.py
index 030dc6d..7c0484d 100755
--- a/ur5_driver/driver.py
+++ b/ur5_driver/driver.py
@@ -6,6 +6,7 @@ import datetime
 import socket, select
 import struct
 import traceback, code
+import optparse
 import SocketServer
 
 import rospy
@@ -14,8 +15,6 @@ from sensor_msgs.msg import JointState
 from control_msgs.msg import FollowJointTrajectoryAction
 from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
 
-HOSTNAME='ur-xx'
-HOSTNAME="10.0.1.20"
 PORT=30001
 
 MSG_OUT = 1
@@ -388,6 +387,13 @@ def main():
         rospy.logfatal("use_sim_time is set!!!")
         sys.exit(1)
 
+    # Parses command line arguments
+    parser = optparse.OptionParser(usage="usage: %prog robot_hostname")
+    (options, args) = parser.parse_args(rospy.myargv()[1:])
+    if len(args) != 1:
+        parser.error("You must specify the robot hostname")
+    robot_hostname = args[0]
+
     # Sets up the server for the robot to connect to
     server = TCPServer(("", 50001), CommanderTCPHandler)
     thread_commander = threading.Thread(name="CommanderHandler", target=server.serve_forever)
@@ -408,7 +414,7 @@ def main():
                 rospy.loginfo("Programming the robot")
                 while True:
                 # Sends the program to the robot
-                    sock = socket.create_connection((HOSTNAME, PORT))
+                    sock = socket.create_connection((robot_hostname, PORT))
                     with open('prog') as fin:
                         program = fin.read()
                         sock.sendall(program % {"driver_hostname": socket.getfqdn()})
-- 
GitLab