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 Namespace Reference

Functions

def generate_launch_description ()
 

Function Documentation

◆ generate_launch_description()

def environment.generate_launch_description ( )
Launch perception nodes.

Definition at line 30 of file environment.launch.py.

31 """
32 Launch perception nodes.
33 """
34
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"
40 )
41
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"
47 )
48
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"
54 )
55
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")
58
59 autoware_auto_launch_pkg_prefix = get_package_share_directory(
60 'autoware_auto_launch')
61
62 euclidean_cluster_param_file = os.path.join(
63 autoware_auto_launch_pkg_prefix, 'param/component_style/euclidean_cluster.param.yaml')
64
65 ray_ground_classifier_param_file = os.path.join(
66 autoware_auto_launch_pkg_prefix, 'param/component_style/ray_ground_classifier.param.yaml')
67
68 tracking_nodes_param_file = os.path.join(
69 autoware_auto_launch_pkg_prefix, 'param/component_style/tracking_nodes.param.yaml')
70
71 object_detection_tracking_param_file = os.path.join(
72 get_package_share_directory('object_detection_tracking'), 'config/parameters.yaml')
73
74 subsystem_controller_default_param_file = os.path.join(
75 get_package_share_directory('subsystem_controllers'), 'config/environment_perception_controller_config.yaml')
76
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"
82 )
83
84 frame_transformer_param_file = os.path.join(
85 get_package_share_directory('frame_transformer'), 'config/parameters.yaml')
86
87 object_visualizer_param_file = os.path.join(
88 get_package_share_directory('object_visualizer'), 'config/parameters.yaml')
89
90 points_map_filter_param_file = os.path.join(
91 get_package_share_directory('points_map_filter'), 'config/parameters.yaml')
92
93 motion_computation_param_file = os.path.join(
94 get_package_share_directory('motion_computation'), 'config/parameters.yaml')
95
96 env_log_levels = EnvironmentVariable('CARMA_ROS_LOGGING_CONFIG', default_value='{ "default_level" : "WARN" }')
97
98 carma_wm_ctrl_param_file = os.path.join(
99 get_package_share_directory('carma_wm_ctrl'), 'config/parameters.yaml')
100
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"))
103
104 # lidar_perception_container contains all nodes for lidar based object perception
105 # a failure in any one node in the chain would invalidate the rest of it, so they can all be
106 # placed in the same container without reducing fault tolerance
107 # a lifecycle wrapper container is used to ensure autoware.auto nodes adhere to the subsystem_controller's signals
108 lidar_perception_container = ComposableNodeContainer(
109 package='carma_ros2_utils', # rclcpp_components
110 name='perception_points_filter_container',
111 executable='lifecycle_component_wrapper_mt',
112 namespace=GetCurrentNamespace(),
113 composable_node_descriptions=[
114 ComposableNode(
115 package='frame_transformer',
116 plugin='frame_transformer::Node',
117 name='lidar_to_map_frame_transformer',
118 extra_arguments=[
119 {'use_intra_process_comms': True},
120 {'--log-level' : GetLogLevel('frame_transformer', env_log_levels) },
121 {'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
122 ],
123 remappings=[
124 ("input", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/lidar/points_raw" ] ),
125 ("output", "points_in_map"),
126 ("change_state", "disabled_change_state"), # Disable lifecycle topics since this is a lifecycle wrapper container
127 ("get_state", "disabled_get_state") # Disable lifecycle topics since this is a lifecycle wrapper container
128 ],
129 parameters=[
130 { "target_frame" : "map"},
131 { "message_type" : "sensor_msgs/PointCloud2"},
132 { "queue_size" : 1},
133 { "timeout" : 50 },
134 vehicle_config_param_file
135 ]
136 ),
137 ComposableNode(
138 package='points_map_filter',
139 plugin='points_map_filter::Node',
140 name='points_map_filter',
141 extra_arguments=[
142 {'use_intra_process_comms': True},
143 {'--log-level' : GetLogLevel('points_map_filter', env_log_levels) },
144 {'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
145 ],
146 remappings=[
147 ("points_raw", "points_in_map" ),
148 ("filtered_points", "map_filtered_points"),
149 ("lanelet2_map", "semantic_map"),
150 ("change_state", "disabled_change_state"), # Disable lifecycle topics since this is a lifecycle wrapper container
151 ("get_state", "disabled_get_state") # Disable lifecycle topics since this is a lifecycle wrapper container
152 ],
153 parameters=[ points_map_filter_param_file, vehicle_config_param_file ]
154 ),
155 ComposableNode(
156 package='frame_transformer',
157 plugin='frame_transformer::Node',
158 name='lidar_frame_transformer',
159 extra_arguments=[
160 {'use_intra_process_comms': True},
161 {'--log-level' : GetLogLevel('frame_transformer', env_log_levels) },
162 {'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
163 ],
164 remappings=[
165 ("input", "map_filtered_points" ),
166 ("output", "points_in_base_link"),
167 ("change_state", "disabled_change_state"), # Disable lifecycle topics since this is a lifecycle wrapper container
168 ("get_state", "disabled_get_state") # Disable lifecycle topics since this is a lifecycle wrapper container
169 ],
170 parameters=[ frame_transformer_param_file, vehicle_config_param_file ]
171 ),
172 ComposableNode(
173 package='ray_ground_classifier_nodes',
174 name='ray_ground_filter',
175 plugin='autoware::perception::filters::ray_ground_classifier_nodes::RayGroundClassifierCloudNode',
176 extra_arguments=[
177 {'use_intra_process_comms': True},
178 {'--log-level' : GetLogLevel('ray_ground_classifier_nodes', env_log_levels) }
179 ],
180 remappings=[
181 ("points_in", "points_in_base_link"),
182 ("points_nonground", "points_no_ground")
183 ],
184 parameters=[ ray_ground_classifier_param_file, vehicle_config_param_file]
185 ),
186 ComposableNode(
187 package='euclidean_cluster_nodes',
188 name='euclidean_cluster',
189 plugin='autoware::perception::segmentation::euclidean_cluster_nodes::EuclideanClusterNode',
190 extra_arguments=[
191 {'use_intra_process_comms': True},
192 {'--log-level' : GetLogLevel('euclidean_cluster_nodes', env_log_levels) }
193 ],
194 remappings=[
195 ("points_in", "points_no_ground")
196 ],
197 parameters=[ euclidean_cluster_param_file, vehicle_config_param_file]
198 ),
199 ComposableNode(
200 package='object_detection_tracking',
201 plugin='bounding_box_to_detected_object::Node',
202 name='bounding_box_converter',
203 extra_arguments=[
204 {'use_intra_process_comms': True},
205 {'--log-level' : GetLogLevel('object_detection_tracking', env_log_levels) },
206 {'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
207 ],
208 remappings=[
209 ("bounding_boxes", "lidar_bounding_boxes"),
210 ("lidar_detected_objects", "detected_objects"),
211 ],
212 parameters=[vehicle_config_param_file]
213 ),
214 ComposableNode(
215 package='tracking_nodes',
216 plugin='autoware::tracking_nodes::MultiObjectTrackerNode',
217 name='tracking_nodes_node',
218 extra_arguments=[
219 {'use_intra_process_comms': True},
220 {'--log-level' : GetLogLevel('tracking_nodes', env_log_levels) }
221 ],
222 remappings=[
223 ("ego_state", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose_with_covariance" ] ),
224 # TODO note classified_rois1 is the default single camera input topic
225 # TODO when camera detection is added, we will wan to separate this node into a different component to preserve fault tolerance
226 ],
227 parameters=[ tracking_nodes_param_file, vehicle_config_param_file]
228 )
229 ]
230 )
231
232 # carma_external_objects_container contains nodes for object detection and tracking
233 # since these nodes can use different object inputs they are a separate container from the lidar_perception_container
234 # to preserve fault tolerance
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=[
241 ComposableNode(
242 package='carma_wm_ctrl',
243 plugin='carma_wm_ctrl::WMBroadcasterNode',
244 name='carma_wm_broadcaster',
245 extra_arguments=[
246 {'use_intra_process_comms': True},
247 {'--log-level' : GetLogLevel('carma_wm_ctrl', env_log_levels) }
248 ],
249 remappings=[
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" ] )
257 ],
258 parameters=[ carma_wm_ctrl_param_file, vehicle_config_param_file, vehicle_characteristics_param_file ]
259 ),
260 ComposableNode(
261 package='object_detection_tracking',
262 plugin='object::ObjectDetectionTrackingNode',
263 name='external_object',
264 extra_arguments=[
265 {'use_intra_process_comms': True},
266 {'--log-level' : GetLogLevel('object_detection_tracking', env_log_levels) }
267 ],
268 remappings=[
269 ("detected_objects", "tracked_objects"),
270 ],
271 parameters=[ object_detection_tracking_param_file, vehicle_config_param_file]
272 ),
273 ComposableNode(
274 package='object_visualizer',
275 plugin='object_visualizer::Node',
276 name='object_visualizer_node',
277 extra_arguments=[
278 {'use_intra_process_comms': True},
279 {'--log-level' : GetLogLevel('object_visualizer', env_log_levels) }
280 ],
281 remappings=[
282 ("external_objects", "external_object_predictions"),
283 ("external_objects_viz", "fused_external_objects_viz")
284 ],
285 parameters=[ object_visualizer_param_file, vehicle_config_param_file ]
286 ),
287 ComposableNode(
288 package='motion_computation',
289 plugin='motion_computation::MotionComputationNode',
290 name='motion_computation_node',
291 extra_arguments=[
292 {'use_intra_process_comms': True},
293 {'--log-level' : GetLogLevel('motion_computation', env_log_levels) }
294 ],
295 remappings=[
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")
301 ],
302 parameters=[
303 motion_computation_param_file, vehicle_config_param_file
304 ]
305 ),
306 ComposableNode( #CARMA Motion Prediction Visualizer Node
307 package='motion_prediction_visualizer',
308 plugin='motion_prediction_visualizer::Node',
309 name='motion_prediction_visualizer',
310 extra_arguments=[
311 {'use_intra_process_comms': True},
312 {'--log-level' : GetLogLevel('motion_prediction_visualizer', env_log_levels) }
313 ],
314 remappings=[
315 ("external_objects", "external_object_predictions" ),
316 ],
317 parameters=[ vehicle_config_param_file ]
318 ),
319 ComposableNode(
320 package='roadway_objects',
321 plugin='roadway_objects::RoadwayObjectsNode',
322 name='roadway_objects_node',
323 extra_arguments=[
324 {'use_intra_process_comms': True},
325 {'--log-level' : GetLogLevel('roadway_objects', env_log_levels) }
326 ],
327 remappings=[
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" ] )
331 ],
332 parameters = [
333 vehicle_config_param_file
334 ]
335
336 ),
337 ComposableNode(
338 package='traffic_incident_parser',
339 plugin='traffic_incident_parser::TrafficIncidentParserNode',
340 name='traffic_incident_parser_node',
341 extra_arguments=[
342 {'use_intra_process_comms': True},
343 {'--log-level' : GetLogLevel('traffic_incident_parser', env_log_levels) }
344 ],
345 remappings=[
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" ] )
351 ],
352 parameters = [
353 vehicle_config_param_file
354 ]
355
356 ),
357 ]
358 )
359
360 # Vector map loader
361 lanelet2_map_loader_container = ComposableNodeContainer(
362 package='carma_ros2_utils', # rclcpp_components
363 name='lanelet2_map_loader_container',
364 executable='lifecycle_component_wrapper_mt',
365 namespace=GetCurrentNamespace(),
366 composable_node_descriptions=[
367 ComposableNode(
368 package='map_file_ros2',
369 plugin='lanelet2_map_loader::Lanelet2MapLoader',
370 name='lanelet2_map_loader',
371 extra_arguments=[
372 {'use_intra_process_comms': True},
373 {'--log-level' : GetLogLevel('lanelet2_map_loader', env_log_levels) },
374 {'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
375 ],
376 remappings=[
377 ("lanelet_map_bin", "base_map"),
378 ("change_state", "disabled_change_state"), # Disable lifecycle topics since this is a lifecycle wrapper container
379 ("get_state", "disabled_get_state") # Disable lifecycle topics since this is a lifecycle wrapper container
380 ],
381 parameters=[
382 { "lanelet2_filename" : vector_map_file},
383 vehicle_config_param_file
384 ]
385 )
386 ]
387 )
388
389
390 # Vector map visualization
391 lanelet2_map_visualization_container = ComposableNodeContainer(
392 package='carma_ros2_utils', # rclcpp_components
393 name='lanelet2_map_visualization_container',
394 executable='lifecycle_component_wrapper_mt',
395 namespace= GetCurrentNamespace(),
396 composable_node_descriptions=[
397 ComposableNode(
398 package='map_file_ros2',
399 plugin='lanelet2_map_visualization::Lanelet2MapVisualization',
400 name='lanelet2_map_visualization',
401 extra_arguments=[
402 {'use_intra_process_comms': True},
403 {'--log-level' : GetLogLevel('lanelet2_map_visualization', env_log_levels) },
404 {'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
405 ],
406 remappings=[
407 ("lanelet_map_bin", "semantic_map"),
408 ("change_state", "disabled_change_state"), # Disable lifecycle topics since this is a lifecycle wrapper container
409 ("get_state", "disabled_get_state") # Disable lifecycle topics since this is a lifecycle wrapper container
410 ],
411 parameters=[
412 vehicle_config_param_file
413 ]
414 )
415 ]
416 )
417
418 # Cooperative Perception Stack
419 carma_cooperative_perception_container = ComposableNodeContainer(
420 package='carma_ros2_utils', # rclcpp_components
421 name='carma_cooperative_perception_container',
422 executable='carma_component_container_mt',
423 namespace= GetCurrentNamespace(),
424 composable_node_descriptions=[
425 ComposableNode(
426 package='carma_cooperative_perception',
427 plugin='carma_cooperative_perception::ExternalObjectListToDetectionListNode',
428 name='cp_external_object_list_to_detection_list_node',
429 extra_arguments=[
430 {'use_intra_process_comms': True},
431 {'--log-level' : GetLogLevel('cp_external_object_list_to_detection_list_node', env_log_levels) },
432 ],
433 remappings=[
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"),
437 ],
438 parameters=[
439 vehicle_config_param_file
440 ]
441 ),
442 ComposableNode(
443 package='carma_cooperative_perception',
444 plugin='carma_cooperative_perception::ExternalObjectListToSdsmNode',
445 name='cp_external_object_list_to_sdsm_node',
446 extra_arguments=[
447 {'use_intra_process_comms': True},
448 {'--log-level' : GetLogLevel('cp_external_object_list_to_sdsm_node', env_log_levels) },
449 ],
450 remappings=[
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"),
455 ],
456 parameters=[
457 vehicle_config_param_file
458 ]
459 ),
460 ComposableNode(
461 package='carma_cooperative_perception',
462 plugin='carma_cooperative_perception::HostVehicleFilterNode',
463 name='cp_host_vehicle_filter_node',
464 extra_arguments=[
465 {'use_intra_process_comms': True},
466 {'--log-level' : GetLogLevel('cp_host_vehicle_filter_node', env_log_levels) },
467 ],
468 remappings=[
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")
472 ],
473 parameters=[
474 cp_host_vehicle_filter_node_file,
475 vehicle_config_param_file
476 ]
477 ),
478 ComposableNode(
479 package='carma_cooperative_perception',
480 plugin='carma_cooperative_perception::SdsmToDetectionListNode',
481 name='cp_sdsm_to_detection_list_node',
482 extra_arguments=[
483 {'use_intra_process_comms': True},
484 {'--log-level' : GetLogLevel('cp_sdsm_to_detection_list_node', env_log_levels) },
485 ],
486 remappings=[
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"),
491 ],
492 parameters=[
493 vehicle_config_param_file
494 ]
495 ),
496 ComposableNode(
497 package='carma_cooperative_perception',
498 plugin='carma_cooperative_perception::TrackListToExternalObjectListNode',
499 name='cp_track_list_to_external_object_list_node',
500 extra_arguments=[
501 {'use_intra_process_comms': True},
502 {'--log-level' : GetLogLevel('cp_track_list_to_external_object_list_node', env_log_levels) },
503 ],
504 remappings=[
505 ("input/track_list", "cooperative_perception_track_list"),
506 ("output/external_object_list", "fused_external_objects"),
507 ],
508 parameters=[
509 vehicle_config_param_file
510 ]
511 ),
512 ComposableNode(
513 package='carma_cooperative_perception',
514 plugin='carma_cooperative_perception::MultipleObjectTrackerNode',
515 name='cp_multiple_object_tracker_node',
516 extra_arguments=[
517 {'use_intra_process_comms': True},
518 {'--log-level' : GetLogLevel('cp_multiple_object_tracker_node', env_log_levels) },
519 ],
520 remappings=[
521 ("output/track_list", "cooperative_perception_track_list"),
522 ("input/detection_list", "filtered_detection_list"),
523 ],
524 parameters=[
525 cp_multiple_object_tracker_node_file,
526 vehicle_config_param_file
527 ]
528 ),
529
530 ]
531 )
532
533 # subsystem_controller which orchestrates the lifecycle of this subsystem's components
534 subsystem_controller = Node(
535 package='subsystem_controllers',
536 name='environment_perception_controller',
537 executable='environment_perception_controller',
538 parameters=[
539 subsystem_controller_default_param_file,
540 subsystem_controller_param_file,
541 {"use_sim_time" : use_sim_time}],
542 on_exit= Shutdown(), # Mark the subsystem controller as required
543 arguments=['--ros-args', '--log-level', GetLogLevel('subsystem_controllers', env_log_levels)]
544 )
545
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,
557 subsystem_controller
558 ])
def generate_launch_description()