Skip to content

Commit 9b74320

Browse files
Port configuration (#835) (#848)
Added possibility to change the reverse_port, script_sender_port and trajectory_port (cherry picked from commit f16ae2a) Co-authored-by: Felix Durchdewald <[email protected]>
1 parent 753ec85 commit 9b74320

File tree

1 file changed

+34
-2
lines changed

1 file changed

+34
-2
lines changed

ur_robot_driver/launch/ur_control.launch.py

Lines changed: 34 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -71,6 +71,9 @@ def launch_setup(context, *args, **kwargs):
7171
tool_voltage = LaunchConfiguration("tool_voltage")
7272
reverse_ip = LaunchConfiguration("reverse_ip")
7373
script_command_port = LaunchConfiguration("script_command_port")
74+
reverse_port = LaunchConfiguration("reverse_port")
75+
script_sender_port = LaunchConfiguration("script_sender_port")
76+
trajectory_port = LaunchConfiguration("trajectory_port")
7477

7578
joint_limit_params = PathJoinSubstitution(
7679
[FindPackageShare(description_package), "config", ur_type, "joint_limits.yaml"]
@@ -181,6 +184,15 @@ def launch_setup(context, *args, **kwargs):
181184
"script_command_port:=",
182185
script_command_port,
183186
" ",
187+
"reverse_port:=",
188+
reverse_port,
189+
" ",
190+
"script_sender_port:=",
191+
script_sender_port,
192+
" ",
193+
"trajectory_port:=",
194+
trajectory_port,
195+
" ",
184196
]
185197
)
186198
robot_description = {"robot_description": robot_description_content}
@@ -575,8 +587,28 @@ def generate_launch_description():
575587
DeclareLaunchArgument(
576588
"script_command_port",
577589
default_value="50004",
578-
description="Port that will be opened to forward script commands from the driver to the robot",
590+
description="Port that will be opened to forward URScript commands to the robot.",
591+
)
592+
)
593+
declared_arguments.append(
594+
DeclareLaunchArgument(
595+
"reverse_port",
596+
default_value="50001",
597+
description="Port that will be opened to send cyclic instructions from the driver to the robot controller.",
598+
)
599+
)
600+
declared_arguments.append(
601+
DeclareLaunchArgument(
602+
"script_sender_port",
603+
default_value="50002",
604+
description="The driver will offer an interface to query the external_control URScript on this port.",
605+
)
606+
)
607+
declared_arguments.append(
608+
DeclareLaunchArgument(
609+
"trajectory_port",
610+
default_value="50003",
611+
description="Port that will be opened for trajectory control.",
579612
)
580613
)
581-
582614
return LaunchDescription(declared_arguments + [OpaqueFunction(function=launch_setup)])

0 commit comments

Comments
 (0)