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