-
Notifications
You must be signed in to change notification settings - Fork 235
/
ur_control.launch.py
636 lines (611 loc) · 21.1 KB
/
ur_control.launch.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
# Copyright (c) 2021 PickNik, Inc.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
#
# * Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in the
# documentation and/or other materials provided with the distribution.
#
# * Neither the name of the {copyright_holder} nor the names of its
# contributors may be used to endorse or promote products derived from
# this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
# Author: Denis Stogl
from launch_ros.actions import Node
from launch_ros.parameter_descriptions import ParameterFile
from launch_ros.substitutions import FindPackageShare
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, OpaqueFunction
from launch.conditions import IfCondition, UnlessCondition
from launch.substitutions import (
Command,
FindExecutable,
LaunchConfiguration,
PathJoinSubstitution,
)
def launch_setup(context, *args, **kwargs):
# Initialize Arguments
ur_type = LaunchConfiguration("ur_type")
robot_ip = LaunchConfiguration("robot_ip")
safety_limits = LaunchConfiguration("safety_limits")
safety_pos_margin = LaunchConfiguration("safety_pos_margin")
safety_k_position = LaunchConfiguration("safety_k_position")
# General arguments
runtime_config_package = LaunchConfiguration("runtime_config_package")
controllers_file = LaunchConfiguration("controllers_file")
description_package = LaunchConfiguration("description_package")
description_file = LaunchConfiguration("description_file")
tf_prefix = LaunchConfiguration("tf_prefix")
use_mock_hardware = LaunchConfiguration("use_mock_hardware")
mock_sensor_commands = LaunchConfiguration("mock_sensor_commands")
controller_spawner_timeout = LaunchConfiguration("controller_spawner_timeout")
initial_joint_controller = LaunchConfiguration("initial_joint_controller")
activate_joint_controller = LaunchConfiguration("activate_joint_controller")
launch_rviz = LaunchConfiguration("launch_rviz")
headless_mode = LaunchConfiguration("headless_mode")
launch_dashboard_client = LaunchConfiguration("launch_dashboard_client")
use_tool_communication = LaunchConfiguration("use_tool_communication")
tool_parity = LaunchConfiguration("tool_parity")
tool_baud_rate = LaunchConfiguration("tool_baud_rate")
tool_stop_bits = LaunchConfiguration("tool_stop_bits")
tool_rx_idle_chars = LaunchConfiguration("tool_rx_idle_chars")
tool_tx_idle_chars = LaunchConfiguration("tool_tx_idle_chars")
tool_device_name = LaunchConfiguration("tool_device_name")
tool_tcp_port = LaunchConfiguration("tool_tcp_port")
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"]
)
kinematics_params = PathJoinSubstitution(
[
FindPackageShare(description_package),
"config",
ur_type,
"default_kinematics.yaml",
]
)
physical_params = PathJoinSubstitution(
[
FindPackageShare(description_package),
"config",
ur_type,
"physical_parameters.yaml",
]
)
visual_params = PathJoinSubstitution(
[
FindPackageShare(description_package),
"config",
ur_type,
"visual_parameters.yaml",
]
)
script_filename = PathJoinSubstitution(
[
FindPackageShare("ur_client_library"),
"resources",
"external_control.urscript",
]
)
input_recipe_filename = PathJoinSubstitution(
[FindPackageShare("ur_robot_driver"), "resources", "rtde_input_recipe.txt"]
)
output_recipe_filename = PathJoinSubstitution(
[FindPackageShare("ur_robot_driver"), "resources", "rtde_output_recipe.txt"]
)
robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
PathJoinSubstitution([FindPackageShare("ur_robot_driver"), "urdf", description_file]),
" ",
"robot_ip:=",
robot_ip,
" ",
"joint_limit_params:=",
joint_limit_params,
" ",
"kinematics_params:=",
kinematics_params,
" ",
"physical_params:=",
physical_params,
" ",
"visual_params:=",
visual_params,
" ",
"safety_limits:=",
safety_limits,
" ",
"safety_pos_margin:=",
safety_pos_margin,
" ",
"safety_k_position:=",
safety_k_position,
" ",
"name:=",
ur_type,
" ",
"script_filename:=",
script_filename,
" ",
"input_recipe_filename:=",
input_recipe_filename,
" ",
"output_recipe_filename:=",
output_recipe_filename,
" ",
"tf_prefix:=",
tf_prefix,
" ",
"use_mock_hardware:=",
use_mock_hardware,
" ",
"mock_sensor_commands:=",
mock_sensor_commands,
" ",
"headless_mode:=",
headless_mode,
" ",
"use_tool_communication:=",
use_tool_communication,
" ",
"tool_parity:=",
tool_parity,
" ",
"tool_baud_rate:=",
tool_baud_rate,
" ",
"tool_stop_bits:=",
tool_stop_bits,
" ",
"tool_rx_idle_chars:=",
tool_rx_idle_chars,
" ",
"tool_tx_idle_chars:=",
tool_tx_idle_chars,
" ",
"tool_device_name:=",
tool_device_name,
" ",
"tool_tcp_port:=",
tool_tcp_port,
" ",
"tool_voltage:=",
tool_voltage,
" ",
"reverse_ip:=",
reverse_ip,
" ",
"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}
initial_joint_controllers = PathJoinSubstitution(
[FindPackageShare(runtime_config_package), "config", controllers_file]
)
rviz_config_file = PathJoinSubstitution(
[FindPackageShare(description_package), "rviz", "view_robot.rviz"]
)
# define update rate
update_rate_config_file = PathJoinSubstitution(
[
FindPackageShare(runtime_config_package),
"config",
ur_type.perform(context) + "_update_rate.yaml",
]
)
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[
update_rate_config_file,
ParameterFile(initial_joint_controllers, allow_substs=True),
],
output="screen",
)
dashboard_client_node = Node(
package="ur_robot_driver",
condition=IfCondition(launch_dashboard_client) and UnlessCondition(use_mock_hardware),
executable="dashboard_client",
name="dashboard_client",
output="screen",
emulate_tty=True,
parameters=[{"robot_ip": robot_ip}],
)
tool_communication_node = Node(
package="ur_robot_driver",
condition=IfCondition(use_tool_communication),
executable="tool_communication.py",
name="ur_tool_comm",
output="screen",
parameters=[
{
"robot_ip": robot_ip,
"tcp_port": tool_tcp_port,
"device_name": tool_device_name,
}
],
)
urscript_interface = Node(
package="ur_robot_driver",
executable="urscript_interface",
parameters=[{"robot_ip": robot_ip}],
output="screen",
condition=UnlessCondition(use_mock_hardware),
)
controller_stopper_node = Node(
package="ur_robot_driver",
executable="controller_stopper_node",
name="controller_stopper",
output="screen",
emulate_tty=True,
condition=UnlessCondition(use_mock_hardware),
parameters=[
{"headless_mode": headless_mode},
{"joint_controller_active": activate_joint_controller},
{
"consistent_controllers": [
"io_and_status_controller",
"force_torque_sensor_broadcaster",
"joint_state_broadcaster",
"speed_scaling_state_broadcaster",
]
},
],
)
robot_state_publisher_node = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
output="both",
parameters=[robot_description],
)
rviz_node = Node(
package="rviz2",
condition=IfCondition(launch_rviz),
executable="rviz2",
name="rviz2",
output="log",
arguments=["-d", rviz_config_file],
)
# Spawn controllers
def controller_spawner(controllers, active=True):
inactive_flags = ["--inactive"] if not active else []
return Node(
package="controller_manager",
executable="spawner",
arguments=[
"--controller-manager",
"/controller_manager",
"--controller-manager-timeout",
controller_spawner_timeout,
]
+ inactive_flags
+ controllers,
)
controllers_active = [
"joint_state_broadcaster",
"io_and_status_controller",
"speed_scaling_state_broadcaster",
"force_torque_sensor_broadcaster",
]
controllers_inactive = ["forward_position_controller"]
controller_spawners = [controller_spawner(controllers_active)] + [
controller_spawner(controllers_inactive, active=False)
]
# There may be other controllers of the joints, but this is the initially-started one
initial_joint_controller_spawner_started = Node(
package="controller_manager",
executable="spawner",
arguments=[
initial_joint_controller,
"-c",
"/controller_manager",
"--controller-manager-timeout",
controller_spawner_timeout,
],
condition=IfCondition(activate_joint_controller),
)
initial_joint_controller_spawner_stopped = Node(
package="controller_manager",
executable="spawner",
arguments=[
initial_joint_controller,
"-c",
"/controller_manager",
"--controller-manager-timeout",
controller_spawner_timeout,
"--inactive",
],
condition=UnlessCondition(activate_joint_controller),
)
nodes_to_start = [
control_node,
dashboard_client_node,
tool_communication_node,
controller_stopper_node,
urscript_interface,
robot_state_publisher_node,
rviz_node,
initial_joint_controller_spawner_stopped,
initial_joint_controller_spawner_started,
] + controller_spawners
return nodes_to_start
def generate_launch_description():
declared_arguments = []
# UR specific arguments
declared_arguments.append(
DeclareLaunchArgument(
"ur_type",
description="Type/series of used UR robot.",
choices=[
"ur3",
"ur3e",
"ur5",
"ur5e",
"ur10",
"ur10e",
"ur16e",
"ur20",
"ur30",
],
)
)
declared_arguments.append(
DeclareLaunchArgument(
"robot_ip", description="IP address by which the robot can be reached."
)
)
declared_arguments.append(
DeclareLaunchArgument(
"safety_limits",
default_value="true",
description="Enables the safety limits controller if true.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"safety_pos_margin",
default_value="0.15",
description="The margin to lower and upper limits in the safety controller.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"safety_k_position",
default_value="20",
description="k-position factor in the safety controller.",
)
)
# General arguments
declared_arguments.append(
DeclareLaunchArgument(
"runtime_config_package",
default_value="ur_robot_driver",
description='Package with the controller\'s configuration in "config" folder. \
Usually the argument is not set, it enables use of a custom setup.',
)
)
declared_arguments.append(
DeclareLaunchArgument(
"controllers_file",
default_value="ur_controllers.yaml",
description="YAML file with the controllers configuration.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"description_package",
default_value="ur_description",
description="Description package with robot URDF/XACRO files. Usually the argument \
is not set, it enables use of a custom description.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"description_file",
default_value="ur.urdf.xacro",
description="URDF/XACRO description file with the robot.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"tf_prefix",
default_value="",
description="tf_prefix of the joint names, useful for \
multi-robot setup. If changed, also joint names in the controllers' configuration \
have to be updated.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"use_mock_hardware",
default_value="false",
description="Start robot with mock hardware mirroring command to its states.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"mock_sensor_commands",
default_value="false",
description="Enable mock command interfaces for sensors used for simple simulations. \
Used only if 'use_mock_hardware' parameter is true.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"headless_mode",
default_value="false",
description="Enable headless mode for robot control",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"controller_spawner_timeout",
default_value="10",
description="Timeout used when spawning controllers.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"initial_joint_controller",
default_value="scaled_joint_trajectory_controller",
description="Initially loaded robot controller.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"activate_joint_controller",
default_value="true",
description="Activate loaded joint controller.",
)
)
declared_arguments.append(
DeclareLaunchArgument("launch_rviz", default_value="true", description="Launch RViz?")
)
declared_arguments.append(
DeclareLaunchArgument(
"launch_dashboard_client",
default_value="true",
description="Launch Dashboard Client?",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"use_tool_communication",
default_value="false",
description="Only available for e series!",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"tool_parity",
default_value="0",
description="Parity configuration for serial communication. Only effective, if \
use_tool_communication is set to True.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"tool_baud_rate",
default_value="115200",
description="Baud rate configuration for serial communication. Only effective, if \
use_tool_communication is set to True.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"tool_stop_bits",
default_value="1",
description="Stop bits configuration for serial communication. Only effective, if \
use_tool_communication is set to True.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"tool_rx_idle_chars",
default_value="1.5",
description="RX idle chars configuration for serial communication. Only effective, \
if use_tool_communication is set to True.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"tool_tx_idle_chars",
default_value="3.5",
description="TX idle chars configuration for serial communication. Only effective, \
if use_tool_communication is set to True.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"tool_device_name",
default_value="/tmp/ttyUR",
description="File descriptor that will be generated for the tool communication device. \
The user has be be allowed to write to this location. \
Only effective, if use_tool_communication is set to True.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"tool_tcp_port",
default_value="54321",
description="Remote port that will be used for bridging the tool's serial device. \
Only effective, if use_tool_communication is set to True.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"tool_voltage",
default_value="0", # 0 being a conservative value that won't destroy anything
description="Tool voltage that will be setup.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"reverse_ip",
default_value="0.0.0.0",
description="IP that will be used for the robot controller to communicate back to the driver.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"script_command_port",
default_value="50004",
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)])