Skip to content

Commit

Permalink
Port configuration (#835)
Browse files Browse the repository at this point in the history
Added possibility to change the reverse_port, script_sender_port and trajectory_port

(cherry picked from commit f16ae2a)
  • Loading branch information
fdurchdewald authored and mergify[bot] committed Oct 17, 2023
1 parent ebc94cf commit c5a0249
Showing 1 changed file with 34 additions and 2 deletions.
36 changes: 34 additions & 2 deletions ur_robot_driver/launch/ur_control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,9 @@ def launch_setup(context, *args, **kwargs):
tool_voltage = LaunchConfiguration("tool_voltage")
reverse_ip = LaunchConfiguration("reverse_ip")
script_command_port = LaunchConfiguration("script_command_port")
reverse_port = LaunchConfiguration("reverse_port")
script_sender_port = LaunchConfiguration("script_sender_port")
trajectory_port = LaunchConfiguration("trajectory_port")

joint_limit_params = PathJoinSubstitution(
[FindPackageShare(description_package), "config", ur_type, "joint_limits.yaml"]
Expand Down Expand Up @@ -182,6 +185,15 @@ def launch_setup(context, *args, **kwargs):
"script_command_port:=",
script_command_port,
" ",
"reverse_port:=",
reverse_port,
" ",
"script_sender_port:=",
script_sender_port,
" ",
"trajectory_port:=",
trajectory_port,
" ",
]
)
robot_description = {"robot_description": robot_description_content}
Expand Down Expand Up @@ -576,8 +588,28 @@ def generate_launch_description():
DeclareLaunchArgument(
"script_command_port",
default_value="50004",
description="Port that will be opened to forward script commands from the driver to the robot",
description="Port that will be opened to forward URScript commands to the robot.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"reverse_port",
default_value="50001",
description="Port that will be opened to send cyclic instructions from the driver to the robot controller.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"script_sender_port",
default_value="50002",
description="The driver will offer an interface to query the external_control URScript on this port.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"trajectory_port",
default_value="50003",
description="Port that will be opened for trajectory control.",
)
)

return LaunchDescription(declared_arguments + [OpaqueFunction(function=launch_setup)])

0 comments on commit c5a0249

Please sign in to comment.