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.
environment.launch.py
Go to the documentation of this file.
1# Copyright (C) 2021-2022 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
25from launch.actions import DeclareLaunchArgument
26from launch.conditions import IfCondition
27from launch.substitutions import PythonExpression
28from pathlib import PurePath
29import os
30
31
33 """
34 Launch perception nodes.
35 """
36
37 vehicle_config_param_file = LaunchConfiguration('vehicle_config_param_file')
38 declare_vehicle_config_param_file_arg = DeclareLaunchArgument(
39 name = 'vehicle_config_param_file',
40 default_value = "/opt/carma/vehicle/config/VehicleConfigParams.yaml",
41 description = "Path to file contain vehicle configuration parameters"
42 )
43
44 use_sim_time = LaunchConfiguration('use_sim_time')
45 declare_use_sim_time_arg = DeclareLaunchArgument(
46 name = 'use_sim_time',
47 default_value = "False",
48 description = "True if simulation mode is on"
49 )
50
51 vehicle_characteristics_param_file = LaunchConfiguration('vehicle_characteristics_param_file')
52 declare_vehicle_characteristics_param_file_arg = DeclareLaunchArgument(
53 name = 'vehicle_characteristics_param_file',
54 default_value = "/opt/carma/vehicle/calibration/identifiers/UniqueVehicleParams.yaml",
55 description = "Path to file containing unique vehicle calibrations"
56 )
57
58 vector_map_file = LaunchConfiguration('vector_map_file')
59 declare_vector_map_file = DeclareLaunchArgument(name='vector_map_file', default_value = 'vector_map.osm', description = "Path to the map osm file if using the noupdate load type")
60
61 # When enabled, the vehicle fuses incoming SDSM with its own sensor data to create a more accurate representation of the environment
62 # When turned off, topics get remapped to solely rely on its own sensor data
63 is_cp_mot_enabled = LaunchConfiguration('is_cp_mot_enabled')
64 declare_is_cp_mot_enabled = DeclareLaunchArgument(
65 name='is_cp_mot_enabled',
66 default_value = 'False',
67 description = 'True if user wants Cooperative Perception capability using Multiple Object Tracking to be enabled'
68 )
69
70 # When enabled, the vehicle has lidar detected objects in its external objects list
71 # TODO: Currently the stack is not shutting down automatically https://usdot-carma.atlassian.net.mcas-gov.us/browse/CAR-6109
72 is_autoware_lidar_obj_detection_enabled = LaunchConfiguration('is_autoware_lidar_obj_detection_enabled')
73 declare_is_autoware_lidar_obj_detection_enabled = DeclareLaunchArgument(
74 name='is_autoware_lidar_obj_detection_enabled',
75 default_value = 'False',
76 description = 'True if user wants Autoware Lidar Object Detection to be enabled'
77 )
78
79 autoware_auto_launch_pkg_prefix = get_package_share_directory(
80 'autoware_auto_launch')
81
82 euclidean_cluster_param_file = os.path.join(
83 autoware_auto_launch_pkg_prefix, 'param/component_style/euclidean_cluster.param.yaml')
84
85 ray_ground_classifier_param_file = os.path.join(
86 autoware_auto_launch_pkg_prefix, 'param/component_style/ray_ground_classifier.param.yaml')
87
88 tracking_nodes_param_file = os.path.join(
89 autoware_auto_launch_pkg_prefix, 'param/component_style/tracking_nodes.param.yaml')
90
91 object_detection_tracking_param_file = os.path.join(
92 get_package_share_directory('object_detection_tracking'), 'config/parameters.yaml')
93
94 subsystem_controller_default_param_file = os.path.join(
95 get_package_share_directory('subsystem_controllers'), 'config/environment_perception_controller_config.yaml')
96
97 subsystem_controller_param_file = LaunchConfiguration('subsystem_controller_param_file')
98 declare_subsystem_controller_param_file_arg = DeclareLaunchArgument(
99 name = 'subsystem_controller_param_file',
100 default_value = subsystem_controller_default_param_file,
101 description = "Path to file containing override parameters for the subsystem controller"
102 )
103
104 frame_transformer_param_file = os.path.join(
105 get_package_share_directory('frame_transformer'), 'config/parameters.yaml')
106
107 object_visualizer_param_file = os.path.join(
108 get_package_share_directory('object_visualizer'), 'config/parameters.yaml')
109
110 points_map_filter_param_file = os.path.join(
111 get_package_share_directory('points_map_filter'), 'config/parameters.yaml')
112
113 motion_computation_param_file = os.path.join(
114 get_package_share_directory('motion_computation'), 'config/parameters.yaml')
115
116 env_log_levels = EnvironmentVariable('CARMA_ROS_LOGGING_CONFIG', default_value='{ "default_level" : "WARN" }')
117
118 carma_wm_ctrl_param_file = os.path.join(
119 get_package_share_directory('carma_wm_ctrl'), 'config/parameters.yaml')
120
121 cp_multiple_object_tracker_node_file = str(PurePath(get_package_share_directory("carma_cooperative_perception"), "config/cp_multiple_object_tracker_node.yaml"))
122 cp_host_vehicle_filter_node_file = str(PurePath(get_package_share_directory("carma_cooperative_perception"), "config/cp_host_vehicle_filter_node.yaml"))
123
124 # lidar_perception_container contains all nodes for lidar based object perception
125 # a failure in any one node in the chain would invalidate the rest of it, so they can all be
126 # placed in the same container without reducing fault tolerance
127 # a lifecycle wrapper container is used to ensure autoware.auto nodes adhere to the subsystem_controller's signals
128 # TODO: Currently, the container is shutting down on its own https://usdot-carma.atlassian.net.mcas-gov.us/browse/CAR-6109
129 lidar_perception_container = ComposableNodeContainer(
130 condition=IfCondition(is_autoware_lidar_obj_detection_enabled),
131 package='carma_ros2_utils', # rclcpp_components
132 name='perception_points_filter_container',
133 executable='lifecycle_component_wrapper_mt',
134 namespace=GetCurrentNamespace(),
135 composable_node_descriptions=[
136 ComposableNode(
137 package='frame_transformer',
138 plugin='frame_transformer::Node',
139 name='lidar_to_map_frame_transformer',
140 extra_arguments=[
141 {'use_intra_process_comms': True},
142 {'--log-level' : GetLogLevel('frame_transformer', env_log_levels) },
143 {'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
144 ],
145 remappings=[
146 ("input", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/lidar/points_raw" ] ),
147 ("output", "points_in_map"),
148 ("change_state", "disabled_change_state"), # Disable lifecycle topics since this is a lifecycle wrapper container
149 ("get_state", "disabled_get_state") # Disable lifecycle topics since this is a lifecycle wrapper container
150 ],
151 parameters=[
152 { "target_frame" : "map"},
153 { "message_type" : "sensor_msgs/PointCloud2"},
154 { "queue_size" : 1},
155 { "timeout" : 50 },
156 vehicle_config_param_file
157 ]
158 ),
159 ComposableNode(
160 package='points_map_filter',
161 plugin='points_map_filter::Node',
162 name='points_map_filter',
163 extra_arguments=[
164 {'use_intra_process_comms': True},
165 {'--log-level' : GetLogLevel('points_map_filter', env_log_levels) },
166 {'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
167 ],
168 remappings=[
169 ("points_raw", "points_in_map" ),
170 ("filtered_points", "map_filtered_points"),
171 ("lanelet2_map", "semantic_map"),
172 ("change_state", "disabled_change_state"), # Disable lifecycle topics since this is a lifecycle wrapper container
173 ("get_state", "disabled_get_state") # Disable lifecycle topics since this is a lifecycle wrapper container
174 ],
175 parameters=[ points_map_filter_param_file, vehicle_config_param_file ]
176 ),
177 ComposableNode(
178 package='frame_transformer',
179 plugin='frame_transformer::Node',
180 name='lidar_frame_transformer',
181 extra_arguments=[
182 {'use_intra_process_comms': True},
183 {'--log-level' : GetLogLevel('frame_transformer', env_log_levels) },
184 {'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
185 ],
186 remappings=[
187 ("input", "map_filtered_points" ),
188 ("output", "points_in_base_link"),
189 ("change_state", "disabled_change_state"), # Disable lifecycle topics since this is a lifecycle wrapper container
190 ("get_state", "disabled_get_state") # Disable lifecycle topics since this is a lifecycle wrapper container
191 ],
192 parameters=[ frame_transformer_param_file, vehicle_config_param_file ]
193 ),
194 ComposableNode(
195 package='ray_ground_classifier_nodes',
196 name='ray_ground_filter',
197 plugin='autoware::perception::filters::ray_ground_classifier_nodes::RayGroundClassifierCloudNode',
198 extra_arguments=[
199 {'use_intra_process_comms': True},
200 {'--log-level' : GetLogLevel('ray_ground_classifier_nodes', env_log_levels) }
201 ],
202 remappings=[
203 ("points_in", "points_in_base_link"),
204 ("points_nonground", "points_no_ground")
205 ],
206 parameters=[ ray_ground_classifier_param_file, vehicle_config_param_file]
207 ),
208 ComposableNode(
209 package='euclidean_cluster_nodes',
210 name='euclidean_cluster',
211 plugin='autoware::perception::segmentation::euclidean_cluster_nodes::EuclideanClusterNode',
212 extra_arguments=[
213 {'use_intra_process_comms': True},
214 {'--log-level' : GetLogLevel('euclidean_cluster_nodes', env_log_levels) }
215 ],
216 remappings=[
217 ("points_in", "points_no_ground")
218 ],
219 parameters=[ euclidean_cluster_param_file, vehicle_config_param_file]
220 ),
221 ComposableNode(
222 package='object_detection_tracking',
223 plugin='bounding_box_to_detected_object::Node',
224 name='bounding_box_converter',
225 extra_arguments=[
226 {'use_intra_process_comms': True},
227 {'--log-level' : GetLogLevel('object_detection_tracking', env_log_levels) },
228 {'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
229 ],
230 remappings=[
231 ("bounding_boxes", "lidar_bounding_boxes"),
232 ("lidar_detected_objects", "detected_objects"),
233 ],
234 parameters=[vehicle_config_param_file]
235 ),
236 ComposableNode(
237 package='tracking_nodes',
238 plugin='autoware::tracking_nodes::MultiObjectTrackerNode',
239 name='tracking_nodes_node',
240 extra_arguments=[
241 {'use_intra_process_comms': True},
242 {'--log-level' : GetLogLevel('tracking_nodes', env_log_levels) }
243 ],
244 remappings=[
245 ("ego_state", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose_with_covariance" ] ),
246 # TODO note classified_rois1 is the default single camera input topic
247 # TODO when camera detection is added, we will wan to separate this node into a different component to preserve fault tolerance
248 ],
249 parameters=[ tracking_nodes_param_file, vehicle_config_param_file]
250 )
251 ]
252 )
253
254
255 # carma_external_objects_container contains nodes for object detection and tracking
256 # since these nodes can use different object inputs they are a separate container from the lidar_perception_container
257 # to preserve fault tolerance
258 carma_external_objects_container = ComposableNodeContainer(
259 package='carma_ros2_utils',
260 name='external_objects_container',
261 executable='carma_component_container_mt',
262 namespace=GetCurrentNamespace(),
263 composable_node_descriptions=[
264 ComposableNode(
265 package='carma_wm_ctrl',
266 plugin='carma_wm_ctrl::WMBroadcasterNode',
267 name='carma_wm_broadcaster',
268 extra_arguments=[
269 {'use_intra_process_comms': True},
270 {'--log-level' : GetLogLevel('carma_wm_ctrl', env_log_levels) }
271 ],
272 remappings=[
273 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] ),
274 ("geofence", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_geofence_control" ] ),
275 ("incoming_map", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_map" ] ),
276 ("current_pose", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] ),
277 ("route", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/route" ] ),
278 ("outgoing_geofence_ack", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_mobility_operation" ] ),
279 ("outgoing_geofence_request", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_geofence_request" ] )
280 ],
281 parameters=[ carma_wm_ctrl_param_file, vehicle_config_param_file, vehicle_characteristics_param_file ]
282 ),
283 ComposableNode(
284 package='object_detection_tracking',
285 plugin='object::ObjectDetectionTrackingNode',
286 name='external_object',
287 extra_arguments=[
288 {'use_intra_process_comms': True},
289 {'--log-level' : GetLogLevel('object_detection_tracking', env_log_levels) }
290 ],
291 remappings=[
292 ("detected_objects", "tracked_objects"),
293 ],
294 parameters=[ object_detection_tracking_param_file, vehicle_config_param_file]
295 ),
296 ComposableNode(
297 package='object_visualizer',
298 plugin='object_visualizer::Node',
299 name='object_visualizer_node',
300 extra_arguments=[
301 {'use_intra_process_comms': True},
302 {'--log-level' : GetLogLevel('object_visualizer', env_log_levels) }
303 ],
304 remappings=[
305 ("external_objects", "external_object_predictions"),
306 ("external_objects_viz", "fused_external_objects_viz")
307 ],
308 parameters=[ object_visualizer_param_file, vehicle_config_param_file ]
309 ),
310 ComposableNode(
311 package='motion_computation',
312 plugin='motion_computation::MotionComputationNode',
313 name='motion_computation_node',
314 extra_arguments=[
315 {'use_intra_process_comms': True},
316 {'--log-level' : GetLogLevel('motion_computation', env_log_levels) }
317 ],
318 remappings=[
319 ("incoming_mobility_path", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_mobility_path" ] ),
320 ("incoming_psm", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_psm" ] ),
321 ("incoming_bsm", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_bsm" ] ),
322 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] ),
323 # if CP is enabled, use fused objects to predict movements, otherwise use own sensor's objects
324 ("external_objects", PythonExpression(['"fused_external_objects" if "', is_cp_mot_enabled, '" == "True" else "external_objects"'])),
325 ],
326 parameters=[
327 motion_computation_param_file, vehicle_config_param_file
328 ]
329 ),
330 ComposableNode( #CARMA Motion Prediction Visualizer Node
331 package='motion_prediction_visualizer',
332 plugin='motion_prediction_visualizer::Node',
333 name='motion_prediction_visualizer',
334 extra_arguments=[
335 {'use_intra_process_comms': True},
336 {'--log-level' : GetLogLevel('motion_prediction_visualizer', env_log_levels) }
337 ],
338 remappings=[
339 ("external_objects", "external_object_predictions" ),
340 ],
341 parameters=[ vehicle_config_param_file ]
342 ),
343 ComposableNode(
344 package='traffic_incident_parser',
345 plugin='traffic_incident_parser::TrafficIncidentParserNode',
346 name='traffic_incident_parser_node',
347 extra_arguments=[
348 {'use_intra_process_comms': True},
349 {'--log-level' : GetLogLevel('traffic_incident_parser', env_log_levels) }
350 ],
351 remappings=[
352 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] ),
353 ("geofence", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_geofence_control" ] ),
354 ("incoming_mobility_operation", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_mobility_operation" ] ),
355 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] ),
356 ("route", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/route" ] )
357 ],
358 parameters = [
359 vehicle_config_param_file
360 ]
361
362 ),
363 ]
364 )
365
366 # Vector map loader
367 lanelet2_map_loader_container = ComposableNodeContainer(
368 package='carma_ros2_utils', # rclcpp_components
369 name='lanelet2_map_loader_container',
370 executable='lifecycle_component_wrapper_mt',
371 namespace=GetCurrentNamespace(),
372 composable_node_descriptions=[
373 ComposableNode(
374 package='map_file_ros2',
375 plugin='lanelet2_map_loader::Lanelet2MapLoader',
376 name='lanelet2_map_loader',
377 extra_arguments=[
378 {'use_intra_process_comms': True},
379 {'--log-level' : GetLogLevel('lanelet2_map_loader', env_log_levels) },
380 {'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
381 ],
382 remappings=[
383 ("lanelet_map_bin", "base_map"),
384 ("change_state", "disabled_change_state"), # Disable lifecycle topics since this is a lifecycle wrapper container
385 ("get_state", "disabled_get_state") # Disable lifecycle topics since this is a lifecycle wrapper container
386 ],
387 parameters=[
388 { "lanelet2_filename" : vector_map_file},
389 vehicle_config_param_file
390 ]
391 )
392 ]
393 )
394
395 # Vector map visualization
396 lanelet2_map_visualization_container = ComposableNodeContainer(
397 package='carma_ros2_utils', # rclcpp_components
398 name='lanelet2_map_visualization_container',
399 executable='lifecycle_component_wrapper_mt',
400 namespace= GetCurrentNamespace(),
401 composable_node_descriptions=[
402 ComposableNode(
403 package='map_file_ros2',
404 plugin='lanelet2_map_visualization::Lanelet2MapVisualization',
405 name='lanelet2_map_visualization',
406 extra_arguments=[
407 {'use_intra_process_comms': True},
408 {'--log-level' : GetLogLevel('lanelet2_map_visualization', env_log_levels) },
409 {'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
410 ],
411 remappings=[
412 ("lanelet_map_bin", "semantic_map"),
413 ("change_state", "disabled_change_state"), # Disable lifecycle topics since this is a lifecycle wrapper container
414 ("get_state", "disabled_get_state") # Disable lifecycle topics since this is a lifecycle wrapper container
415 ],
416 parameters=[
417 vehicle_config_param_file
418 ]
419 )
420 ]
421 )
422
423 # Cooperative Perception Stack
424 carma_cooperative_perception_container = ComposableNodeContainer(
425 condition=IfCondition(is_cp_mot_enabled),
426 package='carma_ros2_utils', # rclcpp_components
427 name='carma_cooperative_perception_container',
428 executable='carma_component_container_mt',
429 namespace= GetCurrentNamespace(),
430 composable_node_descriptions=[
431 ComposableNode(
432 package='carma_cooperative_perception',
433 plugin='carma_cooperative_perception::ExternalObjectListToDetectionListNode',
434 name='cp_external_object_list_to_detection_list_node',
435 extra_arguments=[
436 {'use_intra_process_comms': True},
437 {'--log-level' : GetLogLevel('cp_external_object_list_to_detection_list_node', env_log_levels) },
438 ],
439 remappings=[
440 ("input/georeference", [EnvironmentVariable("CARMA_LOCZ_NS", default_value=""), "/map_param_loader/georeference"]),
441 ("output/detections", "full_detection_list"),
442 ("input/external_objects", "external_objects"),
443 ],
444 parameters=[
445 vehicle_config_param_file
446 ]
447 ),
448 ComposableNode(
449 package='carma_cooperative_perception',
450 plugin='carma_cooperative_perception::ExternalObjectListToSdsmNode',
451 name='cp_external_object_list_to_sdsm_node',
452 extra_arguments=[
453 {'use_intra_process_comms': True},
454 {'--log-level' : GetLogLevel('cp_external_object_list_to_sdsm_node', env_log_levels) },
455 ],
456 remappings=[
457 ("input/georeference", [EnvironmentVariable("CARMA_LOCZ_NS", default_value=""), "/map_param_loader/georeference"]),
458 ("output/sdsms", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_sdsm" ] ),
459 ("input/pose_stamped", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] ),
460 ("input/external_objects", "external_objects"),
461 ],
462 parameters=[
463 vehicle_config_param_file
464 ]
465 ),
466 ComposableNode(
467 package='carma_cooperative_perception',
468 plugin='carma_cooperative_perception::HostVehicleFilterNode',
469 name='cp_host_vehicle_filter_node',
470 extra_arguments=[
471 {'use_intra_process_comms': True},
472 {'--log-level' : GetLogLevel('cp_host_vehicle_filter_node', env_log_levels) },
473 ],
474 remappings=[
475 ("input/host_vehicle_pose", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] ),
476 ("input/detection_list", "full_detection_list"),
477 ("output/detection_list", "filtered_detection_list")
478 ],
479 parameters=[
480 cp_host_vehicle_filter_node_file,
481 vehicle_config_param_file
482 ]
483 ),
484 ComposableNode(
485 package='carma_cooperative_perception',
486 plugin='carma_cooperative_perception::SdsmToDetectionListNode',
487 name='cp_sdsm_to_detection_list_node',
488 extra_arguments=[
489 {'use_intra_process_comms': True},
490 {'--log-level' : GetLogLevel('cp_sdsm_to_detection_list_node', env_log_levels) },
491 ],
492 remappings=[
493 ("input/georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] ),
494 ("input/sdsm", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_sdsm" ] ),
495 ("input/cdasim_clock", "/sim_clock"),
496 ("output/detections", "full_detection_list"),
497 ],
498 parameters=[
499 vehicle_config_param_file
500 ]
501 ),
502 ComposableNode(
503 package='carma_cooperative_perception',
504 plugin='carma_cooperative_perception::TrackListToExternalObjectListNode',
505 name='cp_track_list_to_external_object_list_node',
506 extra_arguments=[
507 {'use_intra_process_comms': True},
508 {'--log-level' : GetLogLevel('cp_track_list_to_external_object_list_node', env_log_levels) },
509 ],
510 remappings=[
511 ("input/track_list", "cooperative_perception_track_list"),
512 ("output/external_object_list", "fused_external_objects"),
513 ],
514 parameters=[
515 vehicle_config_param_file
516 ]
517 ),
518 ComposableNode(
519 package='carma_cooperative_perception',
520 plugin='carma_cooperative_perception::MultipleObjectTrackerNode',
521 name='cp_multiple_object_tracker_node',
522 extra_arguments=[
523 {'use_intra_process_comms': True},
524 {'--log-level' : GetLogLevel('cp_multiple_object_tracker_node', env_log_levels) },
525 ],
526 remappings=[
527 ("output/track_list", "cooperative_perception_track_list"),
528 ("input/detection_list", "filtered_detection_list"),
529 ],
530 parameters=[
531 cp_multiple_object_tracker_node_file,
532 vehicle_config_param_file
533 ]
534 ),
535
536 ]
537 )
538
539 # subsystem_controller which orchestrates the lifecycle of this subsystem's components
540 subsystem_controller = Node(
541 package='subsystem_controllers',
542 name='environment_perception_controller',
543 executable='environment_perception_controller',
544 parameters=[
545 subsystem_controller_default_param_file,
546 subsystem_controller_param_file,
547 {"use_sim_time" : use_sim_time}],
548 on_exit= Shutdown(), # Mark the subsystem controller as required
549 arguments=['--ros-args', '--log-level', GetLogLevel('subsystem_controllers', env_log_levels)]
550 )
551
552 return LaunchDescription([
553 declare_vehicle_characteristics_param_file_arg,
554 declare_vehicle_config_param_file_arg,
555 declare_use_sim_time_arg,
556 declare_is_autoware_lidar_obj_detection_enabled,
557 declare_is_cp_mot_enabled,
558 declare_subsystem_controller_param_file_arg,
559 declare_vector_map_file,
560 lidar_perception_container,
561 carma_external_objects_container,
562 lanelet2_map_loader_container,
563 lanelet2_map_visualization_container,
564 carma_cooperative_perception_container,
565 subsystem_controller
566 ])
def generate_launch_description()