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 pathlib
import PurePath
32 Launch perception nodes.
35 vehicle_config_param_file = LaunchConfiguration('vehicle_config_param_file')
36 declare_vehicle_config_param_file_arg = DeclareLaunchArgument(
37 name =
'vehicle_config_param_file',
38 default_value =
"/opt/carma/vehicle/config/VehicleConfigParams.yaml",
39 description =
"Path to file contain vehicle configuration parameters"
42 use_sim_time = LaunchConfiguration(
'use_sim_time')
43 declare_use_sim_time_arg = DeclareLaunchArgument(
44 name =
'use_sim_time',
45 default_value =
"False",
46 description =
"True if simulation mode is on"
49 vehicle_characteristics_param_file = LaunchConfiguration(
'vehicle_characteristics_param_file')
50 declare_vehicle_characteristics_param_file_arg = DeclareLaunchArgument(
51 name =
'vehicle_characteristics_param_file',
52 default_value =
"/opt/carma/vehicle/calibration/identifiers/UniqueVehicleParams.yaml",
53 description =
"Path to file containing unique vehicle calibrations"
56 vector_map_file = LaunchConfiguration(
'vector_map_file')
57 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")
59 autoware_auto_launch_pkg_prefix = get_package_share_directory(
60 'autoware_auto_launch')
62 euclidean_cluster_param_file = os.path.join(
63 autoware_auto_launch_pkg_prefix,
'param/component_style/euclidean_cluster.param.yaml')
65 ray_ground_classifier_param_file = os.path.join(
66 autoware_auto_launch_pkg_prefix,
'param/component_style/ray_ground_classifier.param.yaml')
68 tracking_nodes_param_file = os.path.join(
69 autoware_auto_launch_pkg_prefix,
'param/component_style/tracking_nodes.param.yaml')
71 object_detection_tracking_param_file = os.path.join(
72 get_package_share_directory(
'object_detection_tracking'),
'config/parameters.yaml')
74 subsystem_controller_default_param_file = os.path.join(
75 get_package_share_directory(
'subsystem_controllers'),
'config/environment_perception_controller_config.yaml')
77 subsystem_controller_param_file = LaunchConfiguration(
'subsystem_controller_param_file')
78 declare_subsystem_controller_param_file_arg = DeclareLaunchArgument(
79 name =
'subsystem_controller_param_file',
80 default_value = subsystem_controller_default_param_file,
81 description =
"Path to file containing override parameters for the subsystem controller"
84 frame_transformer_param_file = os.path.join(
85 get_package_share_directory(
'frame_transformer'),
'config/parameters.yaml')
87 object_visualizer_param_file = os.path.join(
88 get_package_share_directory(
'object_visualizer'),
'config/parameters.yaml')
90 points_map_filter_param_file = os.path.join(
91 get_package_share_directory(
'points_map_filter'),
'config/parameters.yaml')
93 motion_computation_param_file = os.path.join(
94 get_package_share_directory(
'motion_computation'),
'config/parameters.yaml')
96 env_log_levels = EnvironmentVariable(
'CARMA_ROS_LOGGING_CONFIG', default_value=
'{ "default_level" : "WARN" }')
98 carma_wm_ctrl_param_file = os.path.join(
99 get_package_share_directory(
'carma_wm_ctrl'),
'config/parameters.yaml')
101 cp_multiple_object_tracker_node_file = str(PurePath(get_package_share_directory(
"carma_cooperative_perception"),
"config/cp_multiple_object_tracker_node.yaml"))
102 cp_host_vehicle_filter_node_file = str(PurePath(get_package_share_directory(
"carma_cooperative_perception"),
"config/cp_host_vehicle_filter_node.yaml"))
108 lidar_perception_container = ComposableNodeContainer(
109 package=
'carma_ros2_utils',
110 name=
'perception_points_filter_container',
111 executable=
'lifecycle_component_wrapper_mt',
112 namespace=GetCurrentNamespace(),
113 composable_node_descriptions=[
115 package=
'frame_transformer',
116 plugin=
'frame_transformer::Node',
117 name=
'lidar_to_map_frame_transformer',
119 {
'use_intra_process_comms':
True},
120 {
'--log-level' : GetLogLevel(
'frame_transformer', env_log_levels) },
121 {
'is_lifecycle_node':
True}
124 (
"input", [ EnvironmentVariable(
'CARMA_INTR_NS', default_value=
''),
"/lidar/points_raw" ] ),
125 (
"output",
"points_in_map"),
126 (
"change_state",
"disabled_change_state"),
127 (
"get_state",
"disabled_get_state")
130 {
"target_frame" :
"map"},
131 {
"message_type" :
"sensor_msgs/PointCloud2"},
134 vehicle_config_param_file
138 package=
'points_map_filter',
139 plugin=
'points_map_filter::Node',
140 name=
'points_map_filter',
142 {
'use_intra_process_comms':
True},
143 {
'--log-level' : GetLogLevel(
'points_map_filter', env_log_levels) },
144 {
'is_lifecycle_node':
True}
147 (
"points_raw",
"points_in_map" ),
148 (
"filtered_points",
"map_filtered_points"),
149 (
"lanelet2_map",
"semantic_map"),
150 (
"change_state",
"disabled_change_state"),
151 (
"get_state",
"disabled_get_state")
153 parameters=[ points_map_filter_param_file, vehicle_config_param_file ]
156 package=
'frame_transformer',
157 plugin=
'frame_transformer::Node',
158 name=
'lidar_frame_transformer',
160 {
'use_intra_process_comms':
True},
161 {
'--log-level' : GetLogLevel(
'frame_transformer', env_log_levels) },
162 {
'is_lifecycle_node':
True}
165 (
"input",
"map_filtered_points" ),
166 (
"output",
"points_in_base_link"),
167 (
"change_state",
"disabled_change_state"),
168 (
"get_state",
"disabled_get_state")
170 parameters=[ frame_transformer_param_file, vehicle_config_param_file ]
173 package=
'ray_ground_classifier_nodes',
174 name=
'ray_ground_filter',
175 plugin=
'autoware::perception::filters::ray_ground_classifier_nodes::RayGroundClassifierCloudNode',
177 {
'use_intra_process_comms':
True},
178 {
'--log-level' : GetLogLevel(
'ray_ground_classifier_nodes', env_log_levels) }
181 (
"points_in",
"points_in_base_link"),
182 (
"points_nonground",
"points_no_ground")
184 parameters=[ ray_ground_classifier_param_file, vehicle_config_param_file]
187 package=
'euclidean_cluster_nodes',
188 name=
'euclidean_cluster',
189 plugin=
'autoware::perception::segmentation::euclidean_cluster_nodes::EuclideanClusterNode',
191 {
'use_intra_process_comms':
True},
192 {
'--log-level' : GetLogLevel(
'euclidean_cluster_nodes', env_log_levels) }
195 (
"points_in",
"points_no_ground")
197 parameters=[ euclidean_cluster_param_file, vehicle_config_param_file]
200 package=
'object_detection_tracking',
201 plugin=
'bounding_box_to_detected_object::Node',
202 name=
'bounding_box_converter',
204 {
'use_intra_process_comms':
True},
205 {
'--log-level' : GetLogLevel(
'object_detection_tracking', env_log_levels) },
206 {
'is_lifecycle_node':
True}
209 (
"bounding_boxes",
"lidar_bounding_boxes"),
210 (
"lidar_detected_objects",
"detected_objects"),
212 parameters=[vehicle_config_param_file]
215 package=
'tracking_nodes',
216 plugin=
'autoware::tracking_nodes::MultiObjectTrackerNode',
217 name=
'tracking_nodes_node',
219 {
'use_intra_process_comms':
True},
220 {
'--log-level' : GetLogLevel(
'tracking_nodes', env_log_levels) }
223 (
"ego_state", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/current_pose_with_covariance" ] ),
227 parameters=[ tracking_nodes_param_file, vehicle_config_param_file]
235 carma_external_objects_container = ComposableNodeContainer(
236 package=
'carma_ros2_utils',
237 name=
'external_objects_container',
238 executable=
'carma_component_container_mt',
239 namespace=GetCurrentNamespace(),
240 composable_node_descriptions=[
242 package=
'carma_wm_ctrl',
243 plugin=
'carma_wm_ctrl::WMBroadcasterNode',
244 name=
'carma_wm_broadcaster',
246 {
'use_intra_process_comms':
True},
247 {
'--log-level' : GetLogLevel(
'carma_wm_ctrl', env_log_levels) }
250 (
"georeference", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/map_param_loader/georeference" ] ),
251 (
"geofence", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_geofence_control" ] ),
252 (
"incoming_map", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_map" ] ),
253 (
"current_pose", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/current_pose" ] ),
254 (
"route", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/route" ] ),
255 (
"outgoing_geofence_ack", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/outgoing_mobility_operation" ] ),
256 (
"outgoing_geofence_request", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/outgoing_geofence_request" ] )
258 parameters=[ carma_wm_ctrl_param_file, vehicle_config_param_file, vehicle_characteristics_param_file ]
261 package=
'object_detection_tracking',
262 plugin=
'object::ObjectDetectionTrackingNode',
263 name=
'external_object',
265 {
'use_intra_process_comms':
True},
266 {
'--log-level' : GetLogLevel(
'object_detection_tracking', env_log_levels) }
269 (
"detected_objects",
"tracked_objects"),
271 parameters=[ object_detection_tracking_param_file, vehicle_config_param_file]
274 package=
'object_visualizer',
275 plugin=
'object_visualizer::Node',
276 name=
'object_visualizer_node',
278 {
'use_intra_process_comms':
True},
279 {
'--log-level' : GetLogLevel(
'object_visualizer', env_log_levels) }
282 (
"external_objects",
"external_object_predictions"),
283 (
"external_objects_viz",
"fused_external_objects_viz")
285 parameters=[ object_visualizer_param_file, vehicle_config_param_file ]
288 package=
'motion_computation',
289 plugin=
'motion_computation::MotionComputationNode',
290 name=
'motion_computation_node',
292 {
'use_intra_process_comms':
True},
293 {
'--log-level' : GetLogLevel(
'motion_computation', env_log_levels) }
296 (
"incoming_mobility_path", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_mobility_path" ] ),
297 (
"incoming_psm", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_psm" ] ),
298 (
"incoming_bsm", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_bsm" ] ),
299 (
"georeference", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/map_param_loader/georeference" ] ),
300 (
"external_objects",
"fused_external_objects")
303 motion_computation_param_file, vehicle_config_param_file
307 package=
'motion_prediction_visualizer',
308 plugin=
'motion_prediction_visualizer::Node',
309 name=
'motion_prediction_visualizer',
311 {
'use_intra_process_comms':
True},
312 {
'--log-level' : GetLogLevel(
'motion_prediction_visualizer', env_log_levels) }
315 (
"external_objects",
"external_object_predictions" ),
317 parameters=[ vehicle_config_param_file ]
320 package=
'roadway_objects',
321 plugin=
'roadway_objects::RoadwayObjectsNode',
322 name=
'roadway_objects_node',
324 {
'use_intra_process_comms':
True},
325 {
'--log-level' : GetLogLevel(
'roadway_objects', env_log_levels) }
328 (
"external_objects",
"external_object_predictions"),
329 (
"incoming_spat", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_spat" ] ),
330 (
"route", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/route" ] )
333 vehicle_config_param_file
338 package=
'traffic_incident_parser',
339 plugin=
'traffic_incident_parser::TrafficIncidentParserNode',
340 name=
'traffic_incident_parser_node',
342 {
'use_intra_process_comms':
True},
343 {
'--log-level' : GetLogLevel(
'traffic_incident_parser', env_log_levels) }
346 (
"georeference", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/map_param_loader/georeference" ] ),
347 (
"geofence", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_geofence_control" ] ),
348 (
"incoming_mobility_operation", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_mobility_operation" ] ),
349 (
"incoming_spat", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_spat" ] ),
350 (
"route", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/route" ] )
353 vehicle_config_param_file
361 lanelet2_map_loader_container = ComposableNodeContainer(
362 package=
'carma_ros2_utils',
363 name=
'lanelet2_map_loader_container',
364 executable=
'lifecycle_component_wrapper_mt',
365 namespace=GetCurrentNamespace(),
366 composable_node_descriptions=[
368 package=
'map_file_ros2',
369 plugin=
'lanelet2_map_loader::Lanelet2MapLoader',
370 name=
'lanelet2_map_loader',
372 {
'use_intra_process_comms':
True},
373 {
'--log-level' : GetLogLevel(
'lanelet2_map_loader', env_log_levels) },
374 {
'is_lifecycle_node':
True}
377 (
"lanelet_map_bin",
"base_map"),
378 (
"change_state",
"disabled_change_state"),
379 (
"get_state",
"disabled_get_state")
382 {
"lanelet2_filename" : vector_map_file},
383 vehicle_config_param_file
391 lanelet2_map_visualization_container = ComposableNodeContainer(
392 package=
'carma_ros2_utils',
393 name=
'lanelet2_map_visualization_container',
394 executable=
'lifecycle_component_wrapper_mt',
395 namespace= GetCurrentNamespace(),
396 composable_node_descriptions=[
398 package=
'map_file_ros2',
399 plugin=
'lanelet2_map_visualization::Lanelet2MapVisualization',
400 name=
'lanelet2_map_visualization',
402 {
'use_intra_process_comms':
True},
403 {
'--log-level' : GetLogLevel(
'lanelet2_map_visualization', env_log_levels) },
404 {
'is_lifecycle_node':
True}
407 (
"lanelet_map_bin",
"semantic_map"),
408 (
"change_state",
"disabled_change_state"),
409 (
"get_state",
"disabled_get_state")
412 vehicle_config_param_file
419 carma_cooperative_perception_container = ComposableNodeContainer(
420 package=
'carma_ros2_utils',
421 name=
'carma_cooperative_perception_container',
422 executable=
'carma_component_container_mt',
423 namespace= GetCurrentNamespace(),
424 composable_node_descriptions=[
426 package=
'carma_cooperative_perception',
427 plugin=
'carma_cooperative_perception::ExternalObjectListToDetectionListNode',
428 name=
'cp_external_object_list_to_detection_list_node',
430 {
'use_intra_process_comms':
True},
431 {
'--log-level' : GetLogLevel(
'cp_external_object_list_to_detection_list_node', env_log_levels) },
434 (
"input/georeference", [EnvironmentVariable(
"CARMA_LOCZ_NS", default_value=
""),
"/map_param_loader/georeference"]),
435 (
"output/detections",
"full_detection_list"),
436 (
"input/external_objects",
"external_objects"),
439 vehicle_config_param_file
443 package=
'carma_cooperative_perception',
444 plugin=
'carma_cooperative_perception::ExternalObjectListToSdsmNode',
445 name=
'cp_external_object_list_to_sdsm_node',
447 {
'use_intra_process_comms':
True},
448 {
'--log-level' : GetLogLevel(
'cp_external_object_list_to_sdsm_node', env_log_levels) },
451 (
"input/georeference", [EnvironmentVariable(
"CARMA_LOCZ_NS", default_value=
""),
"/map_param_loader/georeference"]),
452 (
"output/sdsms", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/outgoing_sdsm" ] ),
453 (
"input/pose_stamped", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/current_pose" ] ),
454 (
"input/external_objects",
"external_objects"),
457 vehicle_config_param_file
461 package=
'carma_cooperative_perception',
462 plugin=
'carma_cooperative_perception::HostVehicleFilterNode',
463 name=
'cp_host_vehicle_filter_node',
465 {
'use_intra_process_comms':
True},
466 {
'--log-level' : GetLogLevel(
'cp_host_vehicle_filter_node', env_log_levels) },
469 (
"input/host_vehicle_pose", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/current_pose" ] ),
470 (
"input/detection_list",
"full_detection_list"),
471 (
"output/detection_list",
"filtered_detection_list")
474 cp_host_vehicle_filter_node_file,
475 vehicle_config_param_file
479 package=
'carma_cooperative_perception',
480 plugin=
'carma_cooperative_perception::SdsmToDetectionListNode',
481 name=
'cp_sdsm_to_detection_list_node',
483 {
'use_intra_process_comms':
True},
484 {
'--log-level' : GetLogLevel(
'cp_sdsm_to_detection_list_node', env_log_levels) },
487 (
"input/georeference", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/map_param_loader/georeference" ] ),
488 (
"input/sdsm", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_sdsm" ] ),
489 (
"input/cdasim_clock",
"/sim_clock"),
490 (
"output/detections",
"full_detection_list"),
493 vehicle_config_param_file
497 package=
'carma_cooperative_perception',
498 plugin=
'carma_cooperative_perception::TrackListToExternalObjectListNode',
499 name=
'cp_track_list_to_external_object_list_node',
501 {
'use_intra_process_comms':
True},
502 {
'--log-level' : GetLogLevel(
'cp_track_list_to_external_object_list_node', env_log_levels) },
505 (
"input/track_list",
"cooperative_perception_track_list"),
506 (
"output/external_object_list",
"fused_external_objects"),
509 vehicle_config_param_file
513 package=
'carma_cooperative_perception',
514 plugin=
'carma_cooperative_perception::MultipleObjectTrackerNode',
515 name=
'cp_multiple_object_tracker_node',
517 {
'use_intra_process_comms':
True},
518 {
'--log-level' : GetLogLevel(
'cp_multiple_object_tracker_node', env_log_levels) },
521 (
"output/track_list",
"cooperative_perception_track_list"),
522 (
"input/detection_list",
"filtered_detection_list"),
525 cp_multiple_object_tracker_node_file,
526 vehicle_config_param_file
534 subsystem_controller = Node(
535 package=
'subsystem_controllers',
536 name=
'environment_perception_controller',
537 executable=
'environment_perception_controller',
539 subsystem_controller_default_param_file,
540 subsystem_controller_param_file,
541 {
"use_sim_time" : use_sim_time}],
543 arguments=[
'--ros-args',
'--log-level', GetLogLevel(
'subsystem_controllers', env_log_levels)]
546 return LaunchDescription([
547 declare_vehicle_characteristics_param_file_arg,
548 declare_vehicle_config_param_file_arg,
549 declare_use_sim_time_arg,
550 declare_subsystem_controller_param_file_arg,
551 declare_vector_map_file,
552 lidar_perception_container,
553 carma_external_objects_container,
554 lanelet2_map_loader_container,
555 lanelet2_map_visualization_container,
556 carma_cooperative_perception_container,
def generate_launch_description()