Skip to content

Commit ff5b80e

Browse files
Port configuration (#835) (#847)
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 f499df8 commit ff5b80e

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
@@ -72,6 +72,9 @@ def launch_setup(context, *args, **kwargs):
7272
tool_voltage = LaunchConfiguration("tool_voltage")
7373
reverse_ip = LaunchConfiguration("reverse_ip")
7474
script_command_port = LaunchConfiguration("script_command_port")
75+
reverse_port = LaunchConfiguration("reverse_port")
76+
script_sender_port = LaunchConfiguration("script_sender_port")
77+
trajectory_port = LaunchConfiguration("trajectory_port")
7578

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

0 commit comments

Comments
 (0)