Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
plugins.launch.py
Go to the documentation of this file.
1# Copyright (C) 2022-2023 LEIDOS.
2#
3# Licensed under the Apache License, Version 2.0 (the "License");
4# you may not use this file except in compliance with the License.
5# You may obtain a copy of the License at
6#
7# http://www.apache.org/licenses/LICENSE-2.0
8#
9# Unless required by applicable law or agreed to in writing, software
10# distributed under the License is distributed on an "AS IS" BASIS,
11# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12# See the License for the specific language governing permissions and
13# limitations under the License.
14
15from ament_index_python import get_package_share_directory
16from launch.actions import Shutdown
17from launch import LaunchDescription
18from launch_ros.actions import Node
19from launch_ros.actions import ComposableNodeContainer
20from launch_ros.descriptions import ComposableNode
21from launch.substitutions import EnvironmentVariable
22from carma_ros2_utils.launch.get_log_level import GetLogLevel
23from carma_ros2_utils.launch.get_current_namespace import GetCurrentNamespace
24from launch.substitutions import LaunchConfiguration
25
26import os
27
28from launch.actions import IncludeLaunchDescription
29from launch.launch_description_sources import PythonLaunchDescriptionSource
30from launch.actions import GroupAction
31from launch_ros.actions import set_remap
32from launch.actions import DeclareLaunchArgument
33
34# Launch file for launching the nodes in the CARMA guidance stack
35
37
38 route_file_folder = LaunchConfiguration('route_file_folder')
39 vehicle_calibration_dir = LaunchConfiguration('vehicle_calibration_dir')
40 vehicle_characteristics_param_file = LaunchConfiguration('vehicle_characteristics_param_file')
41 enable_guidance_plugin_validator = LaunchConfiguration('enable_guidance_plugin_validator')
42 strategic_plugins_to_validate = LaunchConfiguration('strategic_plugins_to_validate')
43 tactical_plugins_to_validate = LaunchConfiguration('tactical_plugins_to_validate')
44 control_plugins_to_validate = LaunchConfiguration('control_plugins_to_validate')
45
46 vehicle_config_param_file = LaunchConfiguration('vehicle_config_param_file')
47
48 inlanecruising_plugin_file_path = os.path.join(
49 get_package_share_directory('inlanecruising_plugin'), 'config/parameters.yaml')
50
51 route_following_plugin_file_path = os.path.join(
52 get_package_share_directory('route_following_plugin'), 'config/parameters.yaml')
53
54 stop_and_wait_plugin_param_file = os.path.join(
55 get_package_share_directory('stop_and_wait_plugin'), 'config/parameters.yaml')
56
57 light_controlled_intersection_tactical_plugin_param_file = os.path.join(
58 get_package_share_directory('light_controlled_intersection_tactical_plugin'), 'config/parameters.yaml')
59
60 cooperative_lanechange_param_file = os.path.join(
61 get_package_share_directory('cooperative_lanechange'), 'config/parameters.yaml')
62
63 platoon_strategic_ihp_param_file = os.path.join(
64 get_package_share_directory('platoon_strategic_ihp'), 'config/parameters.yaml')
65
66 sci_strategic_plugin_file_path = os.path.join(
67 get_package_share_directory('sci_strategic_plugin'), 'config/parameters.yaml')
68
69 lci_strategic_plugin_file_path = os.path.join(
70 get_package_share_directory('lci_strategic_plugin'), 'config/parameters.yaml')
71
72 stop_and_dwell_strategic_plugin_container_file_path = os.path.join(
73 get_package_share_directory('stop_and_dwell_strategic_plugin'), 'config/parameters.yaml')
74
75 yield_plugin_file_path = os.path.join(
76 get_package_share_directory('yield_plugin'), 'config/parameters.yaml')
77
78 platoon_tactical_ihp_param_file = os.path.join(
79 get_package_share_directory('platooning_tactical_plugin'), 'config/parameters.yaml')
80
81 approaching_emergency_vehicle_plugin_param_file = os.path.join(
82 get_package_share_directory('approaching_emergency_vehicle_plugin'), 'config/parameters.yaml')
83
84 stop_controlled_intersection_tactical_plugin_file_path = os.path.join(
85 get_package_share_directory('stop_controlled_intersection_tactical_plugin'), 'config/parameters.yaml')
86
87 trajectory_follower_wrapper_param_file = os.path.join(
88 get_package_share_directory('trajectory_follower_wrapper'), 'config/parameters.yaml')
89
90 env_log_levels = EnvironmentVariable('CARMA_ROS_LOGGING_CONFIG', default_value='{ "default_level" : "WARN" }')
91
92 pure_pursuit_tuning_parameters = [vehicle_calibration_dir, "/pure_pursuit/calibration.yaml"]
93
94 unique_vehicle_calibration_params = [vehicle_calibration_dir, "/identifiers/UniqueVehicleParams.yaml"]
95
96 platooning_control_param_file = os.path.join(
97 get_package_share_directory('platooning_control'), 'config/parameters.yaml')
98
99 carma_inlanecruising_plugin_container = ComposableNodeContainer(
100 package='carma_ros2_utils',
101 name='carma_lainlanecruising_plugin_container',
102 executable='carma_component_container_mt',
103 namespace=GetCurrentNamespace(),
104 composable_node_descriptions=[
105 ComposableNode(
106 package='inlanecruising_plugin',
107 plugin='inlanecruising_plugin::InLaneCruisingPluginNode',
108 name='inlanecruising_plugin',
109 extra_arguments=[
110 {'use_intra_process_comms': True},
111 {'--log-level' : GetLogLevel('inlanecruising_plugin', env_log_levels) }
112 ],
113 remappings = [
114 ("semantic_map", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/semantic_map" ] ),
115 ("map_update", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/map_update" ] ),
116 ("roadway_objects", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/roadway_objects" ] ),
117 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] ),
118 ("plugin_discovery", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugin_discovery" ] ),
119 ("route", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/route" ] ),
120 ],
121 parameters=[
122 inlanecruising_plugin_file_path,
123 vehicle_config_param_file
124 ]
125 ),
126 ]
127 )
128
129 carma_route_following_plugin_container = ComposableNodeContainer(
130 package='carma_ros2_utils',
131 name='carma_route_following_plugin_container',
132 executable='carma_component_container_mt',
133 namespace=GetCurrentNamespace(),
134 composable_node_descriptions=[
135
136 ComposableNode(
137 package='route_following_plugin',
138 plugin='route_following_plugin::RouteFollowingPlugin',
139 name='route_following_plugin',
140 extra_arguments=[
141 {'use_intra_process_comms': True},
142 {'--log-level' : GetLogLevel('route_following_plugin', env_log_levels) }
143 ],
144 remappings = [
145 ("semantic_map", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/semantic_map" ] ),
146 ("map_update", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/map_update" ] ),
147 ("roadway_objects", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/roadway_objects" ] ),
148 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] ),
149 ("plugin_discovery", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugin_discovery" ] ),
150 ("route", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/route" ] ),
151 ("current_velocity", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle/twist" ] ),
152 ("maneuver_plan", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/final_maneuver_plan" ] ),
153 ],
154 parameters=[
155 route_following_plugin_file_path,
156 vehicle_config_param_file
157 ]
158 ),
159 ]
160 )
161
162 carma_approaching_emergency_vehicle_plugin_container = ComposableNodeContainer(
163 package='carma_ros2_utils',
164 name='carma_approaching_emergency_vehicle_plugin_container',
165 executable='carma_component_container_mt',
166 namespace=GetCurrentNamespace(),
167 composable_node_descriptions=[
168
169 ComposableNode(
170 package='approaching_emergency_vehicle_plugin',
171 plugin='approaching_emergency_vehicle_plugin::ApproachingEmergencyVehiclePlugin',
172 name='approaching_emergency_vehicle_plugin',
173 extra_arguments=[
174 {'use_intra_process_comms': True},
175 {'--log-level' : GetLogLevel('approaching_emergency_vehicle_plugin', env_log_levels) }
176 ],
177 remappings = [
178 ("semantic_map", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/semantic_map" ] ),
179 ("map_update", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/map_update" ] ),
180 ("roadway_objects", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/roadway_objects" ] ),
181 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] ),
182 ("plugin_discovery", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugin_discovery" ] ),
183 ("route", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/route" ] ),
184 ("state", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/state" ] ),
185 ("approaching_erv_status", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/approaching_erv_status" ] ),
186 ("hazard_light_status", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/hazard_light_status" ] ),
187 ("current_velocity", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle/twist" ] ),
188 ("incoming_bsm", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_bsm" ] ),
189 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] ),
190 ("route_state", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/route_state" ] ),
191 ("outgoing_emergency_vehicle_response", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_emergency_vehicle_response" ] ),
192 ("incoming_emergency_vehicle_ack", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_emergency_vehicle_ack" ])
193 ],
194 parameters=[
195 approaching_emergency_vehicle_plugin_param_file,
196 vehicle_characteristics_param_file,
197 vehicle_config_param_file
198 ]
199 ),
200 ]
201 )
202
203 carma_stop_and_wait_plugin_container = ComposableNodeContainer(
204 package='carma_ros2_utils',
205 name='carma_stop_and_wait_plugin_container',
206 executable='carma_component_container_mt',
207 namespace=GetCurrentNamespace(),
208 composable_node_descriptions=[
209
210 ComposableNode(
211 package='stop_and_wait_plugin',
212 plugin='stop_and_wait_plugin::StopandWaitNode',
213 name='stop_and_wait_plugin',
214 extra_arguments=[
215 {'use_intra_process_comms': True},
216 {'--log-level' : GetLogLevel('stop_and_wait_plugin', env_log_levels) }
217 ],
218 remappings = [
219 ("semantic_map", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/semantic_map" ] ),
220 ("map_update", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/map_update" ] ),
221 ("roadway_objects", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/roadway_objects" ] ),
222 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] ),
223 ("plugin_discovery", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugin_discovery" ] ),
224 ("route", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/route" ] ),
225 ],
226 parameters=[
227 stop_and_wait_plugin_param_file,
228 vehicle_config_param_file
229 ]
230 ),
231 ]
232 )
233
234 carma_sci_strategic_plugin_container = ComposableNodeContainer(
235 package='carma_ros2_utils',
236 name='carma_sci_strategic_plugin_container',
237 executable='carma_component_container_mt',
238 namespace=GetCurrentNamespace(),
239 composable_node_descriptions=[
240 ComposableNode(
241 package='sci_strategic_plugin',
242 plugin='sci_strategic_plugin::SCIStrategicPlugin',
243 name='sci_strategic_plugin',
244 extra_arguments=[
245 {'use_intra_process_comms': True},
246 {'--log-level' : GetLogLevel('sci_strategic_plugin', env_log_levels) }
247 ],
248 remappings = [
249 ("semantic_map", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/semantic_map" ] ),
250 ("map_update", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/map_update" ] ),
251 ("roadway_objects", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/roadway_objects" ] ),
252 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] ),
253 ("plugin_discovery", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugin_discovery" ] ),
254 ("route", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/route" ] ),
255 ("maneuver_plan", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/final_maneuver_plan" ] ),
256 ("outgoing_mobility_operation", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_mobility_operation" ] ),
257 ("incoming_mobility_operation", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_mobility_operation" ] ),
258 ("bsm_outbound", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/bsm_outbound" ] ),
259 ("current_pose", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] ),
260 ],
261 parameters=[
262 sci_strategic_plugin_file_path,
263 vehicle_config_param_file
264 ]
265 ),
266 ]
267 )
268
269 carma_lci_strategic_plugin_container = ComposableNodeContainer(
270 package='carma_ros2_utils',
271 name='carma_lci_strategic_plugin_container',
272 executable='carma_component_container_mt',
273 namespace=GetCurrentNamespace(),
274 composable_node_descriptions=[
275 ComposableNode(
276 package='lci_strategic_plugin',
277 plugin='lci_strategic_plugin::LCIStrategicPlugin',
278 name='lci_strategic_plugin',
279 extra_arguments=[
280 {'use_intra_process_comms': True},
281 {'--log-level' : GetLogLevel('lci_strategic_plugin', env_log_levels) }
282 ],
283 remappings = [
284 ("semantic_map", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/semantic_map" ] ),
285 ("map_update", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/map_update" ] ),
286 ("roadway_objects", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/roadway_objects" ] ),
287 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] ),
288 ("plugin_discovery", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugin_discovery" ] ),
289 ("route", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/route" ] ),
290 ("maneuver_plan", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/final_maneuver_plan" ] ),
291 ("outgoing_mobility_operation", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_mobility_operation" ] ),
292 ("incoming_mobility_operation", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_mobility_operation" ] ),
293 ("bsm_outbound", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/bsm_outbound" ] ),
294 ],
295 parameters=[
296 lci_strategic_plugin_file_path,
297 vehicle_config_param_file,
298 unique_vehicle_calibration_params
299 ]
300 ),
301 ]
302 )
303
304 carma_stop_controlled_intersection_tactical_plugin_container = ComposableNodeContainer(
305 package='carma_ros2_utils',
306 name='carma_stop_controlled_intersection_tactical_plugin_container',
307 executable='carma_component_container_mt',
308 namespace=GetCurrentNamespace(),
309 composable_node_descriptions=[
310 ComposableNode(
311 package='stop_controlled_intersection_tactical_plugin',
312 plugin='stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin',
313 name='stop_controlled_intersection_tactical_plugin',
314 extra_arguments=[
315 {'use_intra_process_comms': True},
316 {'--log-level' : GetLogLevel('stop_controlled_intersection_tactical_plugin', env_log_levels) }
317 ],
318 remappings = [
319 ("semantic_map", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/semantic_map" ] ),
320 ("map_update", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/map_update" ] ),
321 ("roadway_objects", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/roadway_objects" ] ),
322 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] ),
323 ("plugin_discovery", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugin_discovery" ] ),
324 ("route", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/route" ] )
325 ],
326 parameters=[
327 stop_controlled_intersection_tactical_plugin_file_path,
328 vehicle_config_param_file
329 ]
330 ),
331 ]
332 )
333
334 carma_cooperative_lanechange_plugins_container = ComposableNodeContainer(
335 package='carma_ros2_utils',
336 name='carma_cooperative_lanechange_plugins_container',
337 executable='carma_component_container_mt',
338 namespace=GetCurrentNamespace(),
339 composable_node_descriptions=[
340 ComposableNode(
341 package='cooperative_lanechange',
342 plugin='cooperative_lanechange::CooperativeLaneChangePlugin',
343 name='cooperative_lanechange',
344 extra_arguments=[
345 {'use_intra_process_comms': True},
346 {'--log-level' : GetLogLevel('cooperative_lanechange', env_log_levels) }
347 ],
348 remappings = [
349 ("semantic_map", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/semantic_map" ] ),
350 ("map_update", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/map_update" ] ),
351 ("roadway_objects", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/roadway_objects" ] ),
352 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] ),
353 ("plugin_discovery", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugin_discovery" ] ),
354 ("route", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/route" ] ),
355 ("current_velocity", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle/twist" ] ),
356 ("cooperative_lane_change_status", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/cooperative_lane_change_status" ] ),
357 ("bsm_outbound", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/bsm_outbound" ] ),
358 ("outgoing_mobility_request", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_mobility_request" ] ),
359 ("incoming_mobility_response", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_mobility_response" ] ),
360 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] ),
361 ("current_pose", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] )
362 ],
363 parameters=[
364 cooperative_lanechange_param_file,
365 vehicle_characteristics_param_file,
366 vehicle_config_param_file
367 ]
368 ),
369 ]
370 )
371
372 carma_yield_plugin_container = ComposableNodeContainer(
373 package='carma_ros2_utils',
374 name='carma_yield_plugin_container',
375 executable='carma_component_container_mt',
376 namespace=GetCurrentNamespace(),
377 composable_node_descriptions=[
378 ComposableNode(
379 package='yield_plugin',
380 plugin='yield_plugin::YieldPluginNode',
381 name='yield_plugin',
382 extra_arguments=[
383 {'use_intra_process_comms': True},
384 {'--log-level' : GetLogLevel('yield_plugin', env_log_levels) }
385 ],
386 remappings = [
387 ("semantic_map", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/semantic_map" ] ),
388 ("map_update", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/map_update" ] ),
389 ("external_object_predictions", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/external_object_predictions" ] ),
390 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] ),
391 ("plugin_discovery", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugin_discovery" ] ),
392 ("route", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/route" ] ),
393 ("outgoing_mobility_response", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_mobility_response" ] ),
394 ("incoming_mobility_request", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_mobility_request" ] ),
395 ("cooperative_lane_change_status", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/cooperative_lane_change_status" ] ),
396 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference"]),
397 ("bsm_outbound", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/bsm_outbound" ] ),
398 ],
399 parameters=[
400 yield_plugin_file_path,
401 vehicle_config_param_file
402 ]
403 ),
404 ]
405 )
406
407 carma_light_controlled_intersection_plugins_container = ComposableNodeContainer(
408 package='carma_ros2_utils',
409 name='carma_light_controlled_intersection_plugins_container',
410 executable='carma_component_container_mt',
411 namespace=GetCurrentNamespace(),
412 composable_node_descriptions=[
413 ComposableNode(
414 package='light_controlled_intersection_tactical_plugin',
415 plugin='light_controlled_intersection_tactical_plugin::LightControlledIntersectionTransitPluginNode',
416 name='light_controlled_intersection_tactical_plugin',
417 extra_arguments=[
418 {'use_intra_process_comms': True},
419 {'--log-level' : GetLogLevel('light_controlled_intersection_tactical_plugin', env_log_levels) }
420 ],
421 remappings = [
422 ("semantic_map", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/semantic_map" ] ),
423 ("map_update", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/map_update" ] ),
424 ("roadway_objects", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/roadway_objects" ] ),
425 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] ),
426 ("plugin_discovery", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugin_discovery" ] ),
427 ("route", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/route" ] )
428 ],
429 parameters=[
430 vehicle_config_param_file,
431 light_controlled_intersection_tactical_plugin_param_file
432 ]
433 ),
434 ]
435 )
436
437 carma_pure_pursuit_wrapper_container = ComposableNodeContainer(
438 package='carma_ros2_utils',
439 name='carma_pure_pursuit_wrapper_container',
440 executable='carma_component_container_mt',
441 namespace=GetCurrentNamespace(),
442 composable_node_descriptions=[
443 ComposableNode(
444 package='pure_pursuit_wrapper',
445 plugin='pure_pursuit_wrapper::PurePursuitWrapperNode',
446 name='pure_pursuit_wrapper',
447 extra_arguments=[
448 {'use_intra_process_comms': True},
449 {'--log-level' : GetLogLevel('pure_pursuit_wrapper', env_log_levels) }
450 ],
451 remappings = [
452 ("plugin_discovery", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugin_discovery" ] ),
453 ("ctrl_raw", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/ctrl_raw" ] ),
454 ("pure_pursuit_wrapper/plan_trajectory", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugins/pure_pursuit/plan_trajectory" ] ),
455 ("current_pose", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] ),
456 ("vehicle/twist", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle/twist" ] ),
457 ],
458 parameters=[
459 vehicle_characteristics_param_file, #vehicle_response_lag
460 vehicle_config_param_file,
461 pure_pursuit_tuning_parameters
462 ]
463 ),
464 ]
465 )
466
467 trajectory_follower_container = ComposableNodeContainer(
468 package='carma_ros2_utils',
469 name='trajectory_follower_container',
470 executable='carma_component_container_mt',
471 namespace=GetCurrentNamespace(),
472 composable_node_descriptions=[
473 ComposableNode(
474 package='trajectory_follower_nodes',
475 plugin='autoware::motion::control::trajectory_follower_nodes::LatLonMuxer',
476 name='latlon_muxer_node',
477 extra_arguments=[
478 {'use_intra_process_comms': False},
479 {'--log-level' : GetLogLevel('latlon_muxer', env_log_levels) }
480 ],
481 remappings = [
482 ("input/lateral/control_cmd", "trajectory_follower/lateral/control_cmd"),
483 ("input/longitudinal/control_cmd", "trajectory_follower/longitudinal/control_cmd"),
484 ("output/control_cmd", "trajectory_follower/control_cmd")
485 ],
486 parameters=[
487 {'timeout_thr_sec':0.5}
488 ]
489 ),
490 ComposableNode(
491 package='trajectory_follower_nodes',
492 plugin='autoware::motion::control::trajectory_follower_nodes::LateralController',
493 name='lateral_controller_node',
494 extra_arguments=[
495 {'use_intra_process_comms': True},
496 {'--log-level' : GetLogLevel('lateral_controller', env_log_levels) }
497 ],
498 remappings = [
499 ("output/lateral/control_cmd", "trajectory_follower/lateral/control_cmd"),
500 ("input/current_kinematic_state", "trajectory_follower/current_kinematic_state"),
501 ("input/reference_trajectory","trajectory_follower/reference_trajectory" )
502 ],
503 parameters = [
504 [vehicle_calibration_dir, "/trajectory_follower/lateral_controller_defaults.yaml"]
505 ]
506 ),
507 ComposableNode(
508 package='trajectory_follower_nodes',
509 plugin='autoware::motion::control::trajectory_follower_nodes::LongitudinalController',
510 name='longitudinal_controller_node',
511 extra_arguments=[
512 {'use_intra_process_comms': False},
513 {'--log-level' : GetLogLevel('longitudinal_controller', env_log_levels) }
514 ],
515 remappings = [
516 ("output/longitudinal/control_cmd", "trajectory_follower/longitudinal/control_cmd"),
517 ("input/current_trajectory", "trajectory_follower/reference_trajectory"),
518 ("input/current_state", "trajectory_follower/current_kinematic_state")
519 ],
520 parameters = [
521 [vehicle_calibration_dir, "/trajectory_follower/longitudinal_controller_defaults.yaml"]
522 ]
523 )
524 ]
525 )
526 carma_trajectory_follower_wrapper_container = ComposableNodeContainer(
527 package='carma_ros2_utils',
528 name='carma_trajectory_follower_wrapper_container',
529 executable='carma_component_container_mt',
530 namespace=GetCurrentNamespace(),
531 composable_node_descriptions=[
532 ComposableNode(
533 package='trajectory_follower_wrapper',
534 plugin='trajectory_follower_wrapper::TrajectoryFollowerWrapperNode',
535 name='trajectory_follower_wrapper',
536 extra_arguments=[
537 {'use_intra_process_comms': True},
538 {'--log-level' : GetLogLevel('trajectory_follower_wrapper', env_log_levels) }
539 ],
540 remappings = [
541 ("plugin_discovery", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugin_discovery" ] ),
542 ("ctrl_raw", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/ctrl_raw" ] ),
543 ("trajectory_follower_wrapper/plan_trajectory", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugins/trajectory_follower_wrapper/plan_trajectory" ] ),
544 ("current_pose", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] ),
545 ("vehicle/twist", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle/twist" ] ),
546 ],
547 parameters=[
548 vehicle_characteristics_param_file,
549 trajectory_follower_wrapper_param_file
550 ]
551 ),
552 ]
553 )
554
555 platooning_strategic_plugin_container = ComposableNodeContainer(
556 package='carma_ros2_utils',
557 name='platooning_strategic_plugin_container',
558 executable='carma_component_container_mt',
559 namespace=GetCurrentNamespace(),
560 composable_node_descriptions=[
561 ComposableNode(
562 package='platoon_strategic_ihp',
563 plugin='platoon_strategic_ihp::Node',
564 name='platoon_strategic_ihp_node',
565 extra_arguments=[
566 {'use_intra_process_comms': True},
567 {'--log-level' : GetLogLevel('platoon_strategic_ihp', env_log_levels) }
568 ],
569 remappings = [
570 ("semantic_map", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/semantic_map" ] ),
571 ("map_update", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/map_update" ] ),
572 ("roadway_objects", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/roadway_objects" ] ),
573 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] ),
574 ("outgoing_mobility_response", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_mobility_response" ] ),
575 ("outgoing_mobility_request", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_mobility_request" ] ),
576 ("outgoing_mobility_operation", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_mobility_operation" ] ),
577 ("incoming_mobility_request", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_mobility_request" ] ),
578 ("incoming_mobility_response", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_mobility_response" ] ),
579 ("incoming_mobility_operation", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_mobility_operation" ] ),
580 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] ),
581 ("twist_raw", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/twist_raw" ] ),
582 ("platoon_info", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/platoon_info" ] ),
583 ("plugin_discovery", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugin_discovery" ] ),
584 ("route", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/route" ] ),
585 ("current_velocity", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle/twist" ] ),
586 ("current_pose", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] ),
587 ],
588 parameters=[
589 platoon_strategic_ihp_param_file,
590 vehicle_config_param_file
591 ]
592 ),
593 ]
594 )
595
596 platooning_tactical_plugin_container = ComposableNodeContainer(
597 package='carma_ros2_utils',
598 name='platooning_tactical_plugin_container',
599 executable='carma_component_container_mt',
600 namespace=GetCurrentNamespace(),
601 composable_node_descriptions=[
602 ComposableNode(
603 package='platooning_tactical_plugin',
604 plugin='platooning_tactical_plugin::Node',
605 name='platooning_tactical_plugin_node',
606 extra_arguments=[
607 {'use_intra_process_comms': True},
608 {'--log-level' : GetLogLevel('platooning_tactical_plugin', env_log_levels) }
609 ],
610 remappings = [
611 ("semantic_map", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/semantic_map" ] ),
612 ("map_update", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/map_update" ] ),
613 ("roadway_objects", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/roadway_objects" ] ),
614 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] ),
615 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] ),
616 ("plugin_discovery", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugin_discovery" ] ),
617 ("route", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/route" ] ),
618 ],
619 parameters=[ platoon_tactical_ihp_param_file, vehicle_config_param_file ]
620 ),
621 ]
622 )
623
624 platooning_control_plugin_container = ComposableNodeContainer(
625 package='carma_ros2_utils',
626 name='platooning_control_container',
627 executable='carma_component_container_mt',
628 namespace=GetCurrentNamespace(),
629 composable_node_descriptions=[
630 ComposableNode(
631 package='platooning_control',
632 plugin='platooning_control::PlatooningControlPlugin',
633 name='platooning_control',
634 extra_arguments=[
635 {'use_intra_process_comms': True},
636 {'--log-level' : GetLogLevel('platooning_control_plugin', env_log_levels) }
637 ],
638 remappings = [
639 ("plugin_discovery", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugin_discovery" ] ),
640 ("ctrl_raw", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/ctrl_raw" ] ),
641 ("twist_raw", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/twist_raw" ] ),
642 ("platooning_control/plan_trajectory", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugins/platooning_control/plan_trajectory" ] ),
643 ("current_pose", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] ),
644 ("vehicle/twist", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle/twist" ] ),
645 ],
646 parameters=[ platooning_control_param_file, vehicle_config_param_file, unique_vehicle_calibration_params ]
647 )
648 ]
649 )
650
651 carma_stop_and_dwell_strategic_plugin_container = ComposableNodeContainer(
652 package='carma_ros2_utils',
653 name='carma_stop_and_dwell_strategic_plugin_container',
654 executable='carma_component_container_mt',
655 namespace=GetCurrentNamespace(),
656 composable_node_descriptions=[
657 ComposableNode(
658 package='stop_and_dwell_strategic_plugin',
659 plugin='stop_and_dwell_strategic_plugin::StopAndDwellStrategicPlugin',
660 name='stop_and_dwell_strategic_plugin',
661 extra_arguments=[
662 {'use_intra_process_comms': True},
663 {'--log-level' : GetLogLevel('stop_and_dwell_strategic_plugin', env_log_levels) }
664 ],
665 remappings = [
666 ("semantic_map", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/semantic_map" ] ),
667 ("map_update", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/map_update" ] ),
668 ("roadway_objects", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/roadway_objects" ] ),
669 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] ),
670 ("plugin_discovery", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plugin_discovery" ] ),
671 ("route", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/route" ] ),
672 ("maneuver_plan", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/final_maneuver_plan" ] ),
673 ("state", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/state" ] ),
674 ("current_pose", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] ),
675 ],
676 parameters=[
677 stop_and_dwell_strategic_plugin_container_file_path,
678 vehicle_config_param_file
679 ]
680 ),
681 ]
682 )
683
684 intersection_transit_maneuvering_container = ComposableNodeContainer(
685 package='carma_ros2_utils',
686 name='intersection_transit_maneuvering_container',
687 executable='carma_component_container_mt',
688 namespace=GetCurrentNamespace(),
689 composable_node_descriptions=[
690 ComposableNode(
691 package='intersection_transit_maneuvering',
692 plugin='intersection_transit_maneuvering::IntersectionTransitManeuveringNode',
693 name='intersection_transit_maneuvering',
694 extra_arguments=[
695 {'use_intra_process_comms': True},
696 {'--log-level' : GetLogLevel('intersection_transit_maneuvering', env_log_levels) }
697 ],
698 remappings = [],
699 parameters=[
700 vehicle_config_param_file
701 ]
702 ),
703 ]
704 )
705
706 return LaunchDescription([
707 carma_inlanecruising_plugin_container,
708 carma_route_following_plugin_container,
709 carma_approaching_emergency_vehicle_plugin_container,
710 carma_stop_and_wait_plugin_container,
711 carma_sci_strategic_plugin_container,
712 carma_stop_and_dwell_strategic_plugin_container,
713 carma_lci_strategic_plugin_container,
714 carma_stop_controlled_intersection_tactical_plugin_container,
715 carma_cooperative_lanechange_plugins_container,
716 carma_yield_plugin_container,
717 carma_light_controlled_intersection_plugins_container,
718 carma_pure_pursuit_wrapper_container,
719 carma_trajectory_follower_wrapper_container,
720 #platooning_strategic_plugin_container,
721 platooning_tactical_plugin_container,
722 platooning_control_plugin_container,
723 intersection_transit_maneuvering_container,
724 trajectory_follower_container
725
726 ])
def generate_launch_description()