Skip to content

Commit 07b51cf

Browse files
firesurferLennart Nachtigall
andauthored
This commits adds additional configuration fields which are needed for multiarm support: (#47)
- Added trajectory_port - Port needed for the trajectory sending interface - Added non_blocking_read - Takes control of the update rate from ur interface by immediately returning from the read method - Added keep_alive_count field - Configures the amount of allowed reading timeouts on the robot side Additionally it adds the ${prefix} argument for the gpios and the force torque sensor in the ur.ros2_control.xacro file Co-authored-by: Lennart Nachtigall <[email protected]>
1 parent e53ee29 commit 07b51cf

File tree

2 files changed

+25
-10
lines changed

2 files changed

+25
-10
lines changed

urdf/ur.ros2_control.xacro

Lines changed: 16 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,11 @@
1818
reverse_port:=50001
1919
script_sender_port:=50002
2020
reverse_ip:=0.0.0.0
21-
script_command_port:=50004">
21+
script_command_port:=50004
22+
trajectory_port:=50003
23+
non_blocking_read:=false
24+
keep_alive_count:=2
25+
">
2226

2327
<ros2_control name="${name}" type="system">
2428
<hardware>
@@ -35,6 +39,7 @@
3539
</xacro:if>
3640
<xacro:unless value="${use_fake_hardware or sim_gazebo or sim_ignition}">
3741
<plugin>ur_robot_driver/URPositionHardwareInterface</plugin>
42+
<param name="prefix">${prefix}</param>
3843
<param name="robot_ip">${robot_ip}</param>
3944
<param name="script_filename">${script_filename}</param>
4045
<param name="output_recipe_filename">${output_recipe_filename}</param>
@@ -44,8 +49,9 @@
4449
<param name="script_sender_port">${script_sender_port}</param>
4550
<param name="reverse_ip">${reverse_ip}</param>
4651
<param name="script_command_port">${script_command_port}</param>
52+
<param name="trajectory_port">${trajectory_port}</param>
4753
<param name="tf_prefix">"${tf_prefix}"</param>
48-
<param name="non_blocking_read">0</param>
54+
<param name="non_blocking_read">${non_blocking_read}</param>
4955
<param name="servoj_gain">2000</param>
5056
<param name="servoj_lookahead_time">0.03</param>
5157
<param name="use_tool_communication">${use_tool_communication}</param>
@@ -58,6 +64,7 @@
5864
<param name="tool_tx_idle_chars">${tool_tx_idle_chars}</param>
5965
<param name="tool_device_name">${tool_device_name}</param>
6066
<param name="tool_tcp_port">${tool_tcp_port}</param>
67+
<param name="keep_alive_count">${keep_alive_count}</param>
6168
</xacro:unless>
6269
</hardware>
6370
<joint name="${prefix}shoulder_pan_joint">
@@ -158,7 +165,7 @@
158165
</joint>
159166

160167
<xacro:unless value="${sim_gazebo or sim_ignition}">
161-
<sensor name="tcp_fts_sensor">
168+
<sensor name="${prefix}tcp_fts_sensor">
162169
<state_interface name="force.x"/>
163170
<state_interface name="force.y"/>
164171
<state_interface name="force.z"/>
@@ -168,14 +175,14 @@
168175
</sensor>
169176

170177
<!-- NOTE The following are joints used only for testing with fake hardware and will change in the future -->
171-
<gpio name="speed_scaling">
178+
<gpio name="${prefix}speed_scaling">
172179
<state_interface name="speed_scaling_factor"/>
173180
<param name="initial_speed_scaling_factor">1</param>
174181
<command_interface name="target_speed_fraction_cmd"/>
175182
<command_interface name="target_speed_fraction_async_success"/>
176183
</gpio>
177184

178-
<gpio name="gpio">
185+
<gpio name="${prefix}gpio">
179186
<command_interface name="standard_digital_output_cmd_0"/>
180187
<command_interface name="standard_digital_output_cmd_1"/>
181188
<command_interface name="standard_digital_output_cmd_2"/>
@@ -284,25 +291,25 @@
284291
<state_interface name="program_running"/>
285292
</gpio>
286293

287-
<gpio name="payload">
294+
<gpio name="${prefix}payload">
288295
<command_interface name="mass"/>
289296
<command_interface name="cog.x"/>
290297
<command_interface name="cog.y"/>
291298
<command_interface name="cog.z"/>
292299
<command_interface name="payload_async_success"/>
293300
</gpio>
294301

295-
<gpio name="resend_robot_program">
302+
<gpio name="${prefix}resend_robot_program">
296303
<command_interface name="resend_robot_program_cmd"/>
297304
<command_interface name="resend_robot_program_async_success"/>
298305
</gpio>
299306

300-
<gpio name="zero_ftsensor">
307+
<gpio name="${prefix}zero_ftsensor">
301308
<command_interface name="zero_ftsensor_cmd"/>
302309
<command_interface name="zero_ftsensor_async_success"/>
303310
</gpio>
304311

305-
<gpio name="system_interface">
312+
<gpio name="${prefix}system_interface">
306313
<state_interface name="initialized"/>
307314
</gpio>
308315

urdf/ur_macro.xacro

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -88,7 +88,12 @@
8888
reverse_port:=50001
8989
script_sender_port:=50002
9090
reverse_ip:=0.0.0.0
91-
script_command_port:=50004">
91+
script_command_port:=50004
92+
trajectory_port:=50003
93+
non_blocking_read:=false
94+
keep_alive_count:=2"
95+
96+
>
9297

9398
<!-- Load configuration data from the provided .yaml files -->
9499
<xacro:read_model_data
@@ -129,6 +134,9 @@
129134
script_sender_port="${script_sender_port}"
130135
reverse_ip="${reverse_ip}"
131136
script_command_port="${script_command_port}"
137+
trajectory_port="${trajectory_port}"
138+
non_blocking_read="${non_blocking_read}"
139+
keep_alive_count="${keep_alive_count}"
132140
/>
133141

134142
<!-- Add URDF transmission elements (for ros_control) -->

0 commit comments

Comments
 (0)