Skip to content

Commit a926789

Browse files
khssnvFelix Exner
authored andcommitted
'reverse_port' and 'script_sender_port' parameters (#57)
Adds parameters for reverse_port and script_sender_port. This was implemented by @khssnv Thanks!
1 parent 2698977 commit a926789

File tree

12 files changed

+131
-9
lines changed

12 files changed

+131
-9
lines changed

ur_robot_driver/doc/ROS_INTERFACE.md

Lines changed: 73 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,10 @@ Standalone launchfile to startup a ur3e. This requires a robot reachable via a n
3232

3333
Use the description in limited mode (Every axis rotates from -PI to PI)
3434

35+
* "**reverse_port**" (default: "50001")
36+
37+
Port that will be opened by the driver to allow direct communication between the driver and the robot controller.
38+
3539
* "**robot_description_file**" (default: "$(find ur_e_description)/launch/ur3e_upload.launch")
3640

3741
Robot description launch file.
@@ -40,6 +44,10 @@ Standalone launchfile to startup a ur3e. This requires a robot reachable via a n
4044

4145
IP address by which the robot can be reached.
4246

47+
* "**script_sender_port**" (default: "50002")
48+
49+
The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately.
50+
4351
* "**stopped_controllers**" (default: "pos_traj_controller")
4452

4553
Controllers that are initally loaded, but not started.
@@ -113,6 +121,10 @@ Standalone launchfile to startup a ur10 robot. This requires a robot reachable v
113121

114122
Use the description in limited mode (Every axis rotates from -PI to PI)
115123

124+
* "**reverse_port**" (default: "50001")
125+
126+
Port that will be opened by the driver to allow direct communication between the driver and the robot controller.
127+
116128
* "**robot_description_file**" (default: "$(find ur_description)/launch/ur10_upload.launch")
117129

118130
Robot description launch file.
@@ -121,6 +133,10 @@ Standalone launchfile to startup a ur10 robot. This requires a robot reachable v
121133

122134
IP address by which the robot can be reached.
123135

136+
* "**script_sender_port**" (default: "50002")
137+
138+
The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately.
139+
124140
* "**stopped_controllers**" (default: "pos_traj_controller")
125141

126142
Controllers that are initally loaded, but not started.
@@ -158,6 +174,10 @@ Robot bringup launchfile without the robot description. Include this, if you wan
158174

159175
Please add description. See file "launch/ur_control.launch".
160176

177+
* "**reverse_port**" (default: "50001")
178+
179+
Port that will be opened by the driver to allow direct communication between the driver and the robot controller.
180+
161181
* "**robot_ip**" (Required)
162182

163183
IP address by which the robot can be reached.
@@ -170,6 +190,10 @@ Robot bringup launchfile without the robot description. Include this, if you wan
170190

171191
Recipe file used for the RTDE-outputs. Only change this if you know what you're doing.
172192

193+
* "**script_sender_port**" (default: "50002")
194+
195+
The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately.
196+
173197
* "**stopped_controllers**" (default: "pos_traj_controller")
174198

175199
Controllers that are initally loaded, but not started.
@@ -247,6 +271,10 @@ Launchfile that starts a robot description with robot_state publisher and the dr
247271

248272
Use the description in limited mode (Every axis rotates from -PI to PI)
249273

274+
* "**reverse_port**" (default: "50001")
275+
276+
Port that will be opened by the driver to allow direct communication between the driver and the robot controller.
277+
250278
* "**robot_description_file**" (Required)
251279

252280
Robot description launch file.
@@ -255,6 +283,10 @@ Launchfile that starts a robot description with robot_state publisher and the dr
255283

256284
IP address by which the robot can be reached.
257285

286+
* "**script_sender_port**" (default: "50002")
287+
288+
The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately.
289+
258290
* "**stopped_controllers**" (default: "pos_traj_controller")
259291

260292
Controllers that are initally loaded, but not started.
@@ -328,6 +360,10 @@ Standalone launchfile to startup a ur5 robot. This requires a robot reachable vi
328360

329361
Use the description in limited mode (Every axis rotates from -PI to PI)
330362

363+
* "**reverse_port**" (default: "50001")
364+
365+
Port that will be opened by the driver to allow direct communication between the driver and the robot controller.
366+
331367
* "**robot_description_file**" (default: "$(find ur_description)/launch/ur5_upload.launch")
332368

333369
Robot description launch file.
@@ -336,6 +372,10 @@ Standalone launchfile to startup a ur5 robot. This requires a robot reachable vi
336372

337373
IP address by which the robot can be reached.
338374

375+
* "**script_sender_port**" (default: "50002")
376+
377+
The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately.
378+
339379
* "**stopped_controllers**" (default: "pos_traj_controller")
340380

341381
Controllers that are initally loaded, but not started.
@@ -373,6 +413,10 @@ Standalone launchfile to startup a ur5e robot. This requires a robot reachable v
373413

374414
Use the description in limited mode (Every axis rotates from -PI to PI)
375415

416+
* "**reverse_port**" (default: "50001")
417+
418+
Port that will be opened by the driver to allow direct communication between the driver and the robot controller.
419+
376420
* "**robot_description_file**" (default: "$(find ur_e_description)/launch/ur5e_upload.launch")
377421

378422
Robot description launch file.
@@ -381,6 +425,10 @@ Standalone launchfile to startup a ur5e robot. This requires a robot reachable v
381425

382426
IP address by which the robot can be reached.
383427

428+
* "**script_sender_port**" (default: "50002")
429+
430+
The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately.
431+
384432
* "**stopped_controllers**" (default: "pos_traj_controller")
385433

386434
Controllers that are initally loaded, but not started.
@@ -454,6 +502,10 @@ Standalone launchfile to startup a ur5 robot. This requires a robot reachable vi
454502

455503
Use the description in limited mode (Every axis rotates from -PI to PI)
456504

505+
* "**reverse_port**" (default: "50001")
506+
507+
Port that will be opened by the driver to allow direct communication between the driver and the robot controller.
508+
457509
* "**robot_description_file**" (default: "$(find ur_description)/launch/ur3_upload.launch")
458510

459511
Robot description launch file.
@@ -462,6 +514,10 @@ Standalone launchfile to startup a ur5 robot. This requires a robot reachable vi
462514

463515
IP address by which the robot can be reached.
464516

517+
* "**script_sender_port**" (default: "50002")
518+
519+
The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately.
520+
465521
* "**stopped_controllers**" (default: "pos_traj_controller")
466522

467523
Controllers that are initally loaded, but not started.
@@ -499,6 +555,10 @@ Standalone launchfile to startup a ur10e robot. This requires a robot reachable
499555

500556
Use the description in limited mode (Every axis rotates from -PI to PI)
501557

558+
* "**reverse_port**" (default: "50001")
559+
560+
Port that will be opened by the driver to allow direct communication between the driver and the robot controller.
561+
502562
* "**robot_description_file**" (default: "$(find ur_e_description)/launch/ur10e_upload.launch")
503563

504564
Robot description launch file.
@@ -507,6 +567,10 @@ Standalone launchfile to startup a ur10e robot. This requires a robot reachable
507567

508568
IP address by which the robot can be reached.
509569

570+
* "**script_sender_port**" (default: "50002")
571+
572+
The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately.
573+
510574
* "**stopped_controllers**" (default: "pos_traj_controller")
511575

512576
Controllers that are initally loaded, but not started.
@@ -702,6 +766,10 @@ This is the actual driver node containing the ROS-Control stack. Interfaces docu
702766

703767
Path to the file containing the recipe used for requesting RTDE outputs.
704768

769+
* "**reverse_port**" (Required)
770+
771+
Port that will be opened to communicate between the driver and the robot controller.
772+
705773
* "**robot_ip**" (Required)
706774

707775
The robot's IP address.
@@ -710,9 +778,13 @@ This is the actual driver node containing the ROS-Control stack. Interfaces docu
710778

711779
Path to the urscript code that will be sent to the robot.
712780

781+
* "**script_sender_port**" (Required)
782+
783+
The driver will offer an interface to receive the program's URScript on this port.
784+
713785
* "**tf_prefix**" (default: "")
714786

715-
Please add description. See hardware_interface.cpp line number: 68
787+
Please add description. See hardware_interface.cpp line number: 74
716788

717789

718790

ur_robot_driver/include/ur_robot_driver/ur/ur_driver.h

Lines changed: 13 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -58,10 +58,15 @@ class UrDriver
5858
* \param tool_comm_setup Configuration for using the tool communication.
5959
* \param calibration_checksum Expected checksum of calibration. Will be matched against the
6060
* calibration reported by the robot.
61+
* \param reverse_port Port that will be opened by the driver to allow direct communication between the driver
62+
* and the robot controller.
63+
* \param script_sending_port The driver will offer an interface to receive the program's URScript on this port. If
64+
* the robot cannot connect to this port, `External Control` will stop immediately.
6165
*/
6266
UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
6367
const std::string& input_recipe_file, std::function<void(bool)> handle_program_state, bool headless_mode,
64-
std::unique_ptr<ToolCommSetup> tool_comm_setup, const std::string& calibration_checksum = "");
68+
std::unique_ptr<ToolCommSetup> tool_comm_setup, const std::string& calibration_checksum = "",
69+
const uint32_t reverse_port = 50001, const uint32_t script_sender_port = 50002);
6570
/*!
6671
* \brief Constructs a new UrDriver object.
6772
*
@@ -73,12 +78,17 @@ class UrDriver
7378
* \param headless_mode Parameter to control if the driver should be started in headless mode.
7479
* \param calibration_checksum Expected checksum of calibration. Will be matched against the
7580
* calibration reported by the robot.
81+
* \param reverse_port Port that will be opened by the driver to allow direct communication between the driver
82+
* and the robot controller
83+
* \param script_sending_port The driver will offer an interface to receive the program's URScript on this port.
84+
* If the robot cannot connect to this port, `External Control` will stop immediately.
7685
*/
7786
UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
7887
const std::string& input_recipe_file, std::function<void(bool)> handle_program_state, bool headless_mode,
79-
const std::string& calibration_checksum = "")
88+
const std::string& calibration_checksum = "", const uint32_t reverse_port = 50001,
89+
const uint32_t script_sender_port = 50002)
8090
: UrDriver(robot_ip, script_file, output_recipe_file, input_recipe_file, handle_program_state, headless_mode,
81-
std::unique_ptr<ToolCommSetup>{}, calibration_checksum)
91+
std::unique_ptr<ToolCommSetup>{}, calibration_checksum, reverse_port, script_sender_port)
8292
{
8393
}
8494

ur_robot_driver/launch/ur10_bringup.launch

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,8 @@
22
<launch>
33
<arg name="debug" default="false" doc="Debug flag that will get passed on to ur_common.launch"/>
44
<arg name="robot_ip" doc="IP address by which the robot can be reached."/>
5+
<arg name="reverse_port" default="50001" doc="Port that will be opened by the driver to allow direct communication between the driver and the robot controller."/>
6+
<arg name="script_sender_port" default="50002" doc="The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately."/>
57
<arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/>
68
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller" doc="Controllers that are activated by default."/>
79
<arg name="stopped_controllers" default="pos_traj_controller" doc="Controllers that are initally loaded, but not started."/>
@@ -17,6 +19,8 @@
1719
<arg name="controller_config_file" value="$(arg controller_config_file)"/>
1820
<arg name="robot_description_file" value="$(arg robot_description_file)"/>
1921
<arg name="robot_ip" value="$(arg robot_ip)"/>
22+
<arg name="reverse_port" value="$(arg reverse_port)"/>
23+
<arg name="script_sender_port" value="$(arg script_sender_port)"/>
2024
<arg name="kinematics_config" value="$(arg kinematics_config)"/>
2125
<arg name="limited" value="$(arg limited)"/>
2226
<arg name="tf_prefix" value="$(arg tf_prefix)"/>

ur_robot_driver/launch/ur10e_bringup.launch

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,8 @@
33

44
<arg name="debug" default="false" doc="Debug flag that will get passed on to ur_common.launch"/>
55
<arg name="robot_ip" doc="IP address by which the robot can be reached."/>
6+
<arg name="reverse_port" default="50001" doc="Port that will be opened by the driver to allow direct communication between the driver and the robot controller."/>
7+
<arg name="script_sender_port" default="50002" doc="The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately."/>
68
<arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/>
79
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller" doc="Controllers that are activated by default."/>
810
<arg name="stopped_controllers" default="pos_traj_controller" doc="Controllers that are initally loaded, but not started."/>
@@ -28,6 +30,8 @@
2830
<arg name="robot_description_file" value="$(arg robot_description_file)"/>
2931
<arg name="kinematics_config" value="$(arg kinematics_config)"/>
3032
<arg name="robot_ip" value="$(arg robot_ip)"/>
33+
<arg name="reverse_port" value="$(arg reverse_port)"/>
34+
<arg name="script_sender_port" value="$(arg script_sender_port)"/>
3135
<arg name="limited" value="$(arg limited)"/>
3236
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
3337
<arg name="controllers" value="$(arg controllers)"/>

ur_robot_driver/launch/ur3_bringup.launch

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,8 @@
22
<launch>
33
<arg name="debug" default="false" doc="Debug flag that will get passed on to ur_common.launch"/>
44
<arg name="robot_ip" doc="IP address by which the robot can be reached."/>
5+
<arg name="reverse_port" default="50001" doc="Port that will be opened by the driver to allow direct communication between the driver and the robot controller."/>
6+
<arg name="script_sender_port" default="50002" doc="The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately."/>
57
<arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/>
68
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller" doc="Controllers that are activated by default."/>
79
<arg name="stopped_controllers" default="pos_traj_controller" doc="Controllers that are initally loaded, but not started."/>
@@ -17,6 +19,8 @@
1719
<arg name="controller_config_file" value="$(arg controller_config_file)"/>
1820
<arg name="robot_description_file" value="$(arg robot_description_file)"/>
1921
<arg name="robot_ip" value="$(arg robot_ip)"/>
22+
<arg name="reverse_port" value="$(arg reverse_port)"/>
23+
<arg name="script_sender_port" value="$(arg script_sender_port)"/>
2024
<arg name="kinematics_config" value="$(arg kinematics_config)"/>
2125
<arg name="limited" value="$(arg limited)"/>
2226
<arg name="tf_prefix" value="$(arg tf_prefix)"/>

ur_robot_driver/launch/ur3e_bringup.launch

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,8 @@
22
<launch>
33
<arg name="debug" default="false" doc="Debug flag that will get passed on to ur_common.launch"/>
44
<arg name="robot_ip" doc="IP address by which the robot can be reached."/>
5+
<arg name="reverse_port" default="50001" doc="Port that will be opened by the driver to allow direct communication between the driver and the robot controller."/>
6+
<arg name="script_sender_port" default="50002" doc="The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately."/>
57
<arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/>
68
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller" doc="Controllers that are activated by default."/>
79
<arg name="stopped_controllers" default="pos_traj_controller" doc="Controllers that are initally loaded, but not started."/>
@@ -27,6 +29,8 @@
2729
<arg name="robot_description_file" value="$(arg robot_description_file)"/>
2830
<arg name="kinematics_config" value="$(arg kinematics_config)"/>
2931
<arg name="robot_ip" value="$(arg robot_ip)"/>
32+
<arg name="reverse_port" value="$(arg reverse_port)"/>
33+
<arg name="script_sender_port" value="$(arg script_sender_port)"/>
3034
<arg name="limited" value="$(arg limited)"/>
3135
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
3236
<arg name="controllers" value="$(arg controllers)"/>

ur_robot_driver/launch/ur5_bringup.launch

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,8 @@
22
<launch>
33
<arg name="debug" default="false" doc="Debug flag that will get passed on to ur_common.launch"/>
44
<arg name="robot_ip" doc="IP address by which the robot can be reached."/>
5+
<arg name="reverse_port" default="50001" doc="Port that will be opened by the driver to allow direct communication between the driver and the robot controller."/>
6+
<arg name="script_sender_port" default="50002" doc="The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately."/>
57
<arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/>
68
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller" doc="Controllers that are activated by default."/>
79
<arg name="stopped_controllers" default="pos_traj_controller" doc="Controllers that are initally loaded, but not started."/>
@@ -17,6 +19,8 @@
1719
<arg name="controller_config_file" value="$(arg controller_config_file)"/>
1820
<arg name="robot_description_file" value="$(arg robot_description_file)"/>
1921
<arg name="robot_ip" value="$(arg robot_ip)"/>
22+
<arg name="reverse_port" value="$(arg reverse_port)"/>
23+
<arg name="script_sender_port" value="$(arg script_sender_port)"/>
2024
<arg name="kinematics_config" value="$(arg kinematics_config)"/>
2125
<arg name="limited" value="$(arg limited)"/>
2226
<arg name="tf_prefix" value="$(arg tf_prefix)"/>

ur_robot_driver/launch/ur5e_bringup.launch

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,8 @@
22
<launch>
33
<arg name="debug" default="false" doc="Debug flag that will get passed on to ur_common.launch"/>
44
<arg name="robot_ip" doc="IP address by which the robot can be reached."/>
5+
<arg name="reverse_port" default="50001" doc="Port that will be opened by the driver to allow direct communication between the driver and the robot controller."/>
6+
<arg name="script_sender_port" default="50002" doc="The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately."/>
57
<arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/>
68
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller" doc="Controllers that are activated by default."/>
79
<arg name="stopped_controllers" default="pos_traj_controller" doc="Controllers that are initally loaded, but not started."/>
@@ -27,6 +29,8 @@
2729
<arg name="robot_description_file" value="$(arg robot_description_file)"/>
2830
<arg name="kinematics_config" value="$(arg kinematics_config)"/>
2931
<arg name="robot_ip" value="$(arg robot_ip)"/>
32+
<arg name="reverse_port" value="$(arg reverse_port)"/>
33+
<arg name="script_sender_port" value="$(arg script_sender_port)"/>
3034
<arg name="limited" value="$(arg limited)"/>
3135
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
3236
<arg name="controllers" value="$(arg controllers)"/>

0 commit comments

Comments
 (0)