|
34 | 34 | from launch_ros.substitutions import FindPackageShare |
35 | 35 |
|
36 | 36 | from launch import LaunchDescription |
37 | | -from launch.actions import DeclareLaunchArgument, OpaqueFunction |
| 37 | +from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription |
38 | 38 | from launch.conditions import IfCondition, UnlessCondition |
39 | 39 | from launch.substitutions import ( |
40 | | - Command, |
41 | | - FindExecutable, |
42 | 40 | LaunchConfiguration, |
43 | 41 | PathJoinSubstitution, |
44 | 42 | ) |
| 43 | +from launch.launch_description_sources import AnyLaunchDescriptionSource |
45 | 44 |
|
46 | 45 |
|
47 | | -def launch_setup(context, *args, **kwargs): |
| 46 | +def launch_setup(): |
48 | 47 | # Initialize Arguments |
49 | 48 | ur_type = LaunchConfiguration("ur_type") |
50 | 49 | robot_ip = LaunchConfiguration("robot_ip") |
51 | | - safety_limits = LaunchConfiguration("safety_limits") |
52 | | - safety_pos_margin = LaunchConfiguration("safety_pos_margin") |
53 | | - safety_k_position = LaunchConfiguration("safety_k_position") |
54 | 50 | # General arguments |
55 | | - runtime_config_package = LaunchConfiguration("runtime_config_package") |
56 | 51 | controllers_file = LaunchConfiguration("controllers_file") |
57 | | - description_package = LaunchConfiguration("description_package") |
58 | | - description_file = LaunchConfiguration("description_file") |
59 | | - tf_prefix = LaunchConfiguration("tf_prefix") |
| 52 | + description_launchfile = LaunchConfiguration("description_launchfile") |
60 | 53 | use_mock_hardware = LaunchConfiguration("use_mock_hardware") |
61 | | - mock_sensor_commands = LaunchConfiguration("mock_sensor_commands") |
62 | 54 | controller_spawner_timeout = LaunchConfiguration("controller_spawner_timeout") |
63 | 55 | initial_joint_controller = LaunchConfiguration("initial_joint_controller") |
64 | 56 | activate_joint_controller = LaunchConfiguration("activate_joint_controller") |
65 | 57 | launch_rviz = LaunchConfiguration("launch_rviz") |
| 58 | + rviz_config_file = LaunchConfiguration("rviz_config_file") |
66 | 59 | headless_mode = LaunchConfiguration("headless_mode") |
67 | 60 | launch_dashboard_client = LaunchConfiguration("launch_dashboard_client") |
68 | 61 | use_tool_communication = LaunchConfiguration("use_tool_communication") |
69 | | - tool_parity = LaunchConfiguration("tool_parity") |
70 | | - tool_baud_rate = LaunchConfiguration("tool_baud_rate") |
71 | | - tool_stop_bits = LaunchConfiguration("tool_stop_bits") |
72 | | - tool_rx_idle_chars = LaunchConfiguration("tool_rx_idle_chars") |
73 | | - tool_tx_idle_chars = LaunchConfiguration("tool_tx_idle_chars") |
74 | 62 | tool_device_name = LaunchConfiguration("tool_device_name") |
75 | 63 | tool_tcp_port = LaunchConfiguration("tool_tcp_port") |
76 | | - tool_voltage = LaunchConfiguration("tool_voltage") |
77 | | - reverse_ip = LaunchConfiguration("reverse_ip") |
78 | | - script_command_port = LaunchConfiguration("script_command_port") |
79 | | - reverse_port = LaunchConfiguration("reverse_port") |
80 | | - script_sender_port = LaunchConfiguration("script_sender_port") |
81 | | - trajectory_port = LaunchConfiguration("trajectory_port") |
82 | | - |
83 | | - joint_limit_params = PathJoinSubstitution( |
84 | | - [FindPackageShare(description_package), "config", ur_type, "joint_limits.yaml"] |
85 | | - ) |
86 | | - kinematics_params = PathJoinSubstitution( |
87 | | - [ |
88 | | - FindPackageShare(description_package), |
89 | | - "config", |
90 | | - ur_type, |
91 | | - "default_kinematics.yaml", |
92 | | - ] |
93 | | - ) |
94 | | - physical_params = PathJoinSubstitution( |
95 | | - [ |
96 | | - FindPackageShare(description_package), |
97 | | - "config", |
98 | | - ur_type, |
99 | | - "physical_parameters.yaml", |
100 | | - ] |
101 | | - ) |
102 | | - visual_params = PathJoinSubstitution( |
103 | | - [ |
104 | | - FindPackageShare(description_package), |
105 | | - "config", |
106 | | - ur_type, |
107 | | - "visual_parameters.yaml", |
108 | | - ] |
109 | | - ) |
110 | | - script_filename = PathJoinSubstitution( |
111 | | - [ |
112 | | - FindPackageShare("ur_client_library"), |
113 | | - "resources", |
114 | | - "external_control.urscript", |
115 | | - ] |
116 | | - ) |
117 | | - input_recipe_filename = PathJoinSubstitution( |
118 | | - [FindPackageShare("ur_robot_driver"), "resources", "rtde_input_recipe.txt"] |
119 | | - ) |
120 | | - output_recipe_filename = PathJoinSubstitution( |
121 | | - [FindPackageShare("ur_robot_driver"), "resources", "rtde_output_recipe.txt"] |
122 | | - ) |
123 | | - |
124 | | - robot_description_content = Command( |
125 | | - [ |
126 | | - PathJoinSubstitution([FindExecutable(name="xacro")]), |
127 | | - " ", |
128 | | - PathJoinSubstitution([FindPackageShare("ur_robot_driver"), "urdf", description_file]), |
129 | | - " ", |
130 | | - "robot_ip:=", |
131 | | - robot_ip, |
132 | | - " ", |
133 | | - "joint_limit_params:=", |
134 | | - joint_limit_params, |
135 | | - " ", |
136 | | - "kinematics_params:=", |
137 | | - kinematics_params, |
138 | | - " ", |
139 | | - "physical_params:=", |
140 | | - physical_params, |
141 | | - " ", |
142 | | - "visual_params:=", |
143 | | - visual_params, |
144 | | - " ", |
145 | | - "safety_limits:=", |
146 | | - safety_limits, |
147 | | - " ", |
148 | | - "safety_pos_margin:=", |
149 | | - safety_pos_margin, |
150 | | - " ", |
151 | | - "safety_k_position:=", |
152 | | - safety_k_position, |
153 | | - " ", |
154 | | - "name:=", |
155 | | - ur_type, |
156 | | - " ", |
157 | | - "script_filename:=", |
158 | | - script_filename, |
159 | | - " ", |
160 | | - "input_recipe_filename:=", |
161 | | - input_recipe_filename, |
162 | | - " ", |
163 | | - "output_recipe_filename:=", |
164 | | - output_recipe_filename, |
165 | | - " ", |
166 | | - "tf_prefix:=", |
167 | | - tf_prefix, |
168 | | - " ", |
169 | | - "use_mock_hardware:=", |
170 | | - use_mock_hardware, |
171 | | - " ", |
172 | | - "mock_sensor_commands:=", |
173 | | - mock_sensor_commands, |
174 | | - " ", |
175 | | - "headless_mode:=", |
176 | | - headless_mode, |
177 | | - " ", |
178 | | - "use_tool_communication:=", |
179 | | - use_tool_communication, |
180 | | - " ", |
181 | | - "tool_parity:=", |
182 | | - tool_parity, |
183 | | - " ", |
184 | | - "tool_baud_rate:=", |
185 | | - tool_baud_rate, |
186 | | - " ", |
187 | | - "tool_stop_bits:=", |
188 | | - tool_stop_bits, |
189 | | - " ", |
190 | | - "tool_rx_idle_chars:=", |
191 | | - tool_rx_idle_chars, |
192 | | - " ", |
193 | | - "tool_tx_idle_chars:=", |
194 | | - tool_tx_idle_chars, |
195 | | - " ", |
196 | | - "tool_device_name:=", |
197 | | - tool_device_name, |
198 | | - " ", |
199 | | - "tool_tcp_port:=", |
200 | | - tool_tcp_port, |
201 | | - " ", |
202 | | - "tool_voltage:=", |
203 | | - tool_voltage, |
204 | | - " ", |
205 | | - "reverse_ip:=", |
206 | | - reverse_ip, |
207 | | - " ", |
208 | | - "script_command_port:=", |
209 | | - script_command_port, |
210 | | - " ", |
211 | | - "reverse_port:=", |
212 | | - reverse_port, |
213 | | - " ", |
214 | | - "script_sender_port:=", |
215 | | - script_sender_port, |
216 | | - " ", |
217 | | - "trajectory_port:=", |
218 | | - trajectory_port, |
219 | | - " ", |
220 | | - ] |
221 | | - ) |
222 | | - robot_description = {"robot_description": robot_description_content} |
223 | | - |
224 | | - initial_joint_controllers = PathJoinSubstitution( |
225 | | - [FindPackageShare(runtime_config_package), "config", controllers_file] |
226 | | - ) |
227 | | - |
228 | | - rviz_config_file = PathJoinSubstitution( |
229 | | - [FindPackageShare(description_package), "rviz", "view_robot.rviz"] |
230 | | - ) |
231 | | - |
232 | | - # define update rate |
233 | | - update_rate_config_file = PathJoinSubstitution( |
234 | | - [ |
235 | | - FindPackageShare(runtime_config_package), |
236 | | - "config", |
237 | | - ur_type.perform(context) + "_update_rate.yaml", |
238 | | - ] |
239 | | - ) |
240 | 64 |
|
241 | 65 | control_node = Node( |
242 | 66 | package="controller_manager", |
243 | 67 | executable="ros2_control_node", |
244 | 68 | parameters=[ |
245 | | - update_rate_config_file, |
246 | | - ParameterFile(initial_joint_controllers, allow_substs=True), |
| 69 | + LaunchConfiguration("update_rate_config_file"), |
| 70 | + ParameterFile(controllers_file, allow_substs=True), |
247 | 71 | ], |
248 | 72 | output="screen", |
249 | 73 | ) |
@@ -302,13 +126,6 @@ def launch_setup(context, *args, **kwargs): |
302 | 126 | ], |
303 | 127 | ) |
304 | 128 |
|
305 | | - robot_state_publisher_node = Node( |
306 | | - package="robot_state_publisher", |
307 | | - executable="robot_state_publisher", |
308 | | - output="both", |
309 | | - parameters=[robot_description], |
310 | | - ) |
311 | | - |
312 | 129 | rviz_node = Node( |
313 | 130 | package="rviz2", |
314 | 131 | condition=IfCondition(launch_rviz), |
@@ -373,13 +190,21 @@ def controller_spawner(controllers, active=True): |
373 | 190 | condition=UnlessCondition(activate_joint_controller), |
374 | 191 | ) |
375 | 192 |
|
| 193 | + rsp = IncludeLaunchDescription( |
| 194 | + AnyLaunchDescriptionSource(description_launchfile), |
| 195 | + launch_arguments={ |
| 196 | + "robot_ip": robot_ip, |
| 197 | + "ur_type": ur_type, |
| 198 | + }.items(), |
| 199 | + ) |
| 200 | + |
376 | 201 | nodes_to_start = [ |
377 | 202 | control_node, |
378 | 203 | dashboard_client_node, |
379 | 204 | tool_communication_node, |
380 | 205 | controller_stopper_node, |
381 | 206 | urscript_interface, |
382 | | - robot_state_publisher_node, |
| 207 | + rsp, |
383 | 208 | rviz_node, |
384 | 209 | initial_joint_controller_spawner_stopped, |
385 | 210 | initial_joint_controller_spawner_started, |
@@ -435,34 +260,24 @@ def generate_launch_description(): |
435 | 260 | ) |
436 | 261 | ) |
437 | 262 | # General arguments |
438 | | - declared_arguments.append( |
439 | | - DeclareLaunchArgument( |
440 | | - "runtime_config_package", |
441 | | - default_value="ur_robot_driver", |
442 | | - description='Package with the controller\'s configuration in "config" folder. ' |
443 | | - "Usually the argument is not set, it enables use of a custom setup.", |
444 | | - ) |
445 | | - ) |
446 | 263 | declared_arguments.append( |
447 | 264 | DeclareLaunchArgument( |
448 | 265 | "controllers_file", |
449 | | - default_value="ur_controllers.yaml", |
| 266 | + default_value=PathJoinSubstitution( |
| 267 | + [FindPackageShare("ur_robot_driver"), "config", "ur_controllers.yaml"] |
| 268 | + ), |
450 | 269 | description="YAML file with the controllers configuration.", |
451 | 270 | ) |
452 | 271 | ) |
453 | 272 | declared_arguments.append( |
454 | 273 | DeclareLaunchArgument( |
455 | | - "description_package", |
456 | | - default_value="ur_description", |
457 | | - description="Description package with robot URDF/XACRO files. Usually the argument " |
458 | | - "is not set, it enables use of a custom description.", |
459 | | - ) |
460 | | - ) |
461 | | - declared_arguments.append( |
462 | | - DeclareLaunchArgument( |
463 | | - "description_file", |
464 | | - default_value="ur.urdf.xacro", |
465 | | - description="URDF/XACRO description file with the robot.", |
| 274 | + "description_launchfile", |
| 275 | + default_value=PathJoinSubstitution( |
| 276 | + [FindPackageShare("ur_robot_driver"), "launch", "ur_rsp.launch.py"] |
| 277 | + ), |
| 278 | + description="Launchfile (absolute path) providing the description. " |
| 279 | + "The launchfile has to start a robot_state_publisher node that " |
| 280 | + "publishes the description topic.", |
466 | 281 | ) |
467 | 282 | ) |
468 | 283 | declared_arguments.append( |
@@ -520,6 +335,15 @@ def generate_launch_description(): |
520 | 335 | declared_arguments.append( |
521 | 336 | DeclareLaunchArgument("launch_rviz", default_value="true", description="Launch RViz?") |
522 | 337 | ) |
| 338 | + declared_arguments.append( |
| 339 | + DeclareLaunchArgument( |
| 340 | + "rviz_config_file", |
| 341 | + default_value=PathJoinSubstitution( |
| 342 | + [FindPackageShare("ur_description"), "rviz", "view_robot.rviz"] |
| 343 | + ), |
| 344 | + description="RViz config file (absolute path) to use when launching rviz.", |
| 345 | + ) |
| 346 | + ) |
523 | 347 | declared_arguments.append( |
524 | 348 | DeclareLaunchArgument( |
525 | 349 | "launch_dashboard_client", |
@@ -633,4 +457,20 @@ def generate_launch_description(): |
633 | 457 | description="Port that will be opened for trajectory control.", |
634 | 458 | ) |
635 | 459 | ) |
636 | | - return LaunchDescription(declared_arguments + [OpaqueFunction(function=launch_setup)]) |
| 460 | + declared_arguments.append( |
| 461 | + DeclareLaunchArgument( |
| 462 | + name="update_rate_config_file", |
| 463 | + default_value=[ |
| 464 | + PathJoinSubstitution( |
| 465 | + [ |
| 466 | + FindPackageShare("ur_robot_driver"), |
| 467 | + "config", |
| 468 | + ] |
| 469 | + ), |
| 470 | + "/", |
| 471 | + LaunchConfiguration("ur_type"), |
| 472 | + "_update_rate.yaml", |
| 473 | + ], |
| 474 | + ) |
| 475 | + ) |
| 476 | + return LaunchDescription(declared_arguments + launch_setup()) |
0 commit comments