From 2c3e91c95fde2ecfac4d57930b5b37b602cf88bf Mon Sep 17 00:00:00 2001 From: Felix Mauch Date: Mon, 30 Sep 2019 09:03:13 +0200 Subject: [PATCH] tcp_port should also be a private parameter --- ur_rtde_driver/scripts/tool_communication | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ur_rtde_driver/scripts/tool_communication b/ur_rtde_driver/scripts/tool_communication index 14bf5c2..63df853 100755 --- a/ur_rtde_driver/scripts/tool_communication +++ b/ur_rtde_driver/scripts/tool_communication @@ -12,7 +12,7 @@ def main(): # IP address of the robot robot_ip = rospy.get_param("~robot_ip") # Port on which the remote pc (robot) publishes the interface - tcp_port = rospy.get_param("tcp_port", "54321") + tcp_port = rospy.get_param("~tcp_port", "54321") # By default, socat will create a pty in /dev/pts/N with n being an increasing number. # Additionally, a symlink at the given location will be created. Use an absolute path here.