|
18 | 18 | reverse_port:=50001 |
19 | 19 | script_sender_port:=50002 |
20 | 20 | 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 | + "> |
22 | 26 |
|
23 | 27 | <ros2_control name="${name}" type="system"> |
24 | 28 | <hardware> |
|
35 | 39 | </xacro:if> |
36 | 40 | <xacro:unless value="${use_fake_hardware or sim_gazebo or sim_ignition}"> |
37 | 41 | <plugin>ur_robot_driver/URPositionHardwareInterface</plugin> |
| 42 | + <param name="prefix">${prefix}</param> |
38 | 43 | <param name="robot_ip">${robot_ip}</param> |
39 | 44 | <param name="script_filename">${script_filename}</param> |
40 | 45 | <param name="output_recipe_filename">${output_recipe_filename}</param> |
|
44 | 49 | <param name="script_sender_port">${script_sender_port}</param> |
45 | 50 | <param name="reverse_ip">${reverse_ip}</param> |
46 | 51 | <param name="script_command_port">${script_command_port}</param> |
| 52 | + <param name="trajectory_port">${trajectory_port}</param> |
47 | 53 | <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> |
49 | 55 | <param name="servoj_gain">2000</param> |
50 | 56 | <param name="servoj_lookahead_time">0.03</param> |
51 | 57 | <param name="use_tool_communication">${use_tool_communication}</param> |
|
58 | 64 | <param name="tool_tx_idle_chars">${tool_tx_idle_chars}</param> |
59 | 65 | <param name="tool_device_name">${tool_device_name}</param> |
60 | 66 | <param name="tool_tcp_port">${tool_tcp_port}</param> |
| 67 | + <param name="keep_alive_count">${keep_alive_count}</param> |
61 | 68 | </xacro:unless> |
62 | 69 | </hardware> |
63 | 70 | <joint name="${prefix}shoulder_pan_joint"> |
|
158 | 165 | </joint> |
159 | 166 |
|
160 | 167 | <xacro:unless value="${sim_gazebo or sim_ignition}"> |
161 | | - <sensor name="tcp_fts_sensor"> |
| 168 | + <sensor name="${prefix}tcp_fts_sensor"> |
162 | 169 | <state_interface name="force.x"/> |
163 | 170 | <state_interface name="force.y"/> |
164 | 171 | <state_interface name="force.z"/> |
|
168 | 175 | </sensor> |
169 | 176 |
|
170 | 177 | <!-- 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"> |
172 | 179 | <state_interface name="speed_scaling_factor"/> |
173 | 180 | <param name="initial_speed_scaling_factor">1</param> |
174 | 181 | <command_interface name="target_speed_fraction_cmd"/> |
175 | 182 | <command_interface name="target_speed_fraction_async_success"/> |
176 | 183 | </gpio> |
177 | 184 |
|
178 | | - <gpio name="gpio"> |
| 185 | + <gpio name="${prefix}gpio"> |
179 | 186 | <command_interface name="standard_digital_output_cmd_0"/> |
180 | 187 | <command_interface name="standard_digital_output_cmd_1"/> |
181 | 188 | <command_interface name="standard_digital_output_cmd_2"/> |
|
284 | 291 | <state_interface name="program_running"/> |
285 | 292 | </gpio> |
286 | 293 |
|
287 | | - <gpio name="payload"> |
| 294 | + <gpio name="${prefix}payload"> |
288 | 295 | <command_interface name="mass"/> |
289 | 296 | <command_interface name="cog.x"/> |
290 | 297 | <command_interface name="cog.y"/> |
291 | 298 | <command_interface name="cog.z"/> |
292 | 299 | <command_interface name="payload_async_success"/> |
293 | 300 | </gpio> |
294 | 301 |
|
295 | | - <gpio name="resend_robot_program"> |
| 302 | + <gpio name="${prefix}resend_robot_program"> |
296 | 303 | <command_interface name="resend_robot_program_cmd"/> |
297 | 304 | <command_interface name="resend_robot_program_async_success"/> |
298 | 305 | </gpio> |
299 | 306 |
|
300 | | - <gpio name="zero_ftsensor"> |
| 307 | + <gpio name="${prefix}zero_ftsensor"> |
301 | 308 | <command_interface name="zero_ftsensor_cmd"/> |
302 | 309 | <command_interface name="zero_ftsensor_async_success"/> |
303 | 310 | </gpio> |
304 | 311 |
|
305 | | - <gpio name="system_interface"> |
| 312 | + <gpio name="${prefix}system_interface"> |
306 | 313 | <state_interface name="initialized"/> |
307 | 314 | </gpio> |
308 | 315 |
|
|
0 commit comments