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
28from launch.actions
import IncludeLaunchDescription
29from launch.launch_description_sources
import PythonLaunchDescriptionSource
30from launch.actions
import GroupAction
31from launch_ros.actions
import set_remap
32from launch.actions
import DeclareLaunchArgument
38 route_file_folder = LaunchConfiguration(
'route_file_folder')
39 vehicle_calibration_dir = LaunchConfiguration(
'vehicle_calibration_dir')
40 vehicle_characteristics_param_file = LaunchConfiguration(
'vehicle_characteristics_param_file')
41 enable_guidance_plugin_validator = LaunchConfiguration(
'enable_guidance_plugin_validator')
42 strategic_plugins_to_validate = LaunchConfiguration(
'strategic_plugins_to_validate')
43 tactical_plugins_to_validate = LaunchConfiguration(
'tactical_plugins_to_validate')
44 control_plugins_to_validate = LaunchConfiguration(
'control_plugins_to_validate')
46 vehicle_config_param_file = LaunchConfiguration(
'vehicle_config_param_file')
48 inlanecruising_plugin_file_path = os.path.join(
49 get_package_share_directory(
'inlanecruising_plugin'),
'config/parameters.yaml')
51 route_following_plugin_file_path = os.path.join(
52 get_package_share_directory(
'route_following_plugin'),
'config/parameters.yaml')
54 stop_and_wait_plugin_param_file = os.path.join(
55 get_package_share_directory(
'stop_and_wait_plugin'),
'config/parameters.yaml')
57 light_controlled_intersection_tactical_plugin_param_file = os.path.join(
58 get_package_share_directory(
'light_controlled_intersection_tactical_plugin'),
'config/parameters.yaml')
60 cooperative_lanechange_param_file = os.path.join(
61 get_package_share_directory(
'cooperative_lanechange'),
'config/parameters.yaml')
63 platooning_strategic_ihp_param_file = os.path.join(
64 get_package_share_directory(
'platooning_strategic_ihp'),
'config/parameters.yaml')
66 sci_strategic_plugin_file_path = os.path.join(
67 get_package_share_directory(
'sci_strategic_plugin'),
'config/parameters.yaml')
69 lci_strategic_plugin_file_path = os.path.join(
70 get_package_share_directory(
'lci_strategic_plugin'),
'config/parameters.yaml')
72 stop_and_dwell_strategic_plugin_container_file_path = os.path.join(
73 get_package_share_directory(
'stop_and_dwell_strategic_plugin'),
'config/parameters.yaml')
75 yield_plugin_file_path = os.path.join(
76 get_package_share_directory(
'yield_plugin'),
'config/parameters.yaml')
78 platoon_tactical_ihp_param_file = os.path.join(
79 get_package_share_directory(
'platooning_tactical_plugin'),
'config/parameters.yaml')
81 approaching_emergency_vehicle_plugin_param_file = os.path.join(
82 get_package_share_directory(
'approaching_emergency_vehicle_plugin'),
'config/parameters.yaml')
84 stop_controlled_intersection_tactical_plugin_file_path = os.path.join(
85 get_package_share_directory(
'stop_controlled_intersection_tactical_plugin'),
'config/parameters.yaml')
87 trajectory_follower_wrapper_param_file = os.path.join(
88 get_package_share_directory(
'trajectory_follower_wrapper'),
'config/parameters.yaml')
90 env_log_levels = EnvironmentVariable(
'CARMA_ROS_LOGGING_CONFIG', default_value=
'{ "default_level" : "WARN" }')
92 pure_pursuit_tuning_parameters = [vehicle_calibration_dir,
"/pure_pursuit/calibration.yaml"]
94 unique_vehicle_calibration_params = [vehicle_calibration_dir,
"/identifiers/UniqueVehicleParams.yaml"]
96 platooning_control_param_file = os.path.join(
97 get_package_share_directory(
'platooning_control'),
'config/parameters.yaml')
99 carma_inlanecruising_plugin_container = ComposableNodeContainer(
100 package=
'carma_ros2_utils',
101 name=
'carma_lainlanecruising_plugin_container',
102 executable=
'carma_component_container_mt',
103 namespace=GetCurrentNamespace(),
104 composable_node_descriptions=[
106 package=
'inlanecruising_plugin',
107 plugin=
'inlanecruising_plugin::InLaneCruisingPluginNode',
108 name=
'inlanecruising_plugin',
110 {
'use_intra_process_comms':
True},
111 {
'--log-level' : GetLogLevel(
'inlanecruising_plugin', env_log_levels) }
114 (
"semantic_map", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/semantic_map" ] ),
115 (
"map_update", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/map_update" ] ),
116 (
"roadway_objects", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/roadway_objects" ] ),
117 (
"incoming_spat", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_spat" ] ),
118 (
"plugin_discovery", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugin_discovery" ] ),
119 (
"route", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/route" ] ),
122 inlanecruising_plugin_file_path,
123 vehicle_config_param_file
129 carma_route_following_plugin_container = ComposableNodeContainer(
130 package=
'carma_ros2_utils',
131 name=
'carma_route_following_plugin_container',
132 executable=
'carma_component_container_mt',
133 namespace=GetCurrentNamespace(),
134 composable_node_descriptions=[
137 package=
'route_following_plugin',
138 plugin=
'route_following_plugin::RouteFollowingPlugin',
139 name=
'route_following_plugin',
141 {
'use_intra_process_comms':
True},
142 {
'--log-level' : GetLogLevel(
'route_following_plugin', env_log_levels) }
145 (
"semantic_map", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/semantic_map" ] ),
146 (
"map_update", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/map_update" ] ),
147 (
"roadway_objects", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/roadway_objects" ] ),
148 (
"incoming_spat", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_spat" ] ),
149 (
"plugin_discovery", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugin_discovery" ] ),
150 (
"route", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/route" ] ),
151 (
"current_velocity", [ EnvironmentVariable(
'CARMA_INTR_NS', default_value=
''),
"/vehicle/twist" ] ),
152 (
"maneuver_plan", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/final_maneuver_plan" ] ),
155 route_following_plugin_file_path,
156 vehicle_config_param_file
162 carma_approaching_emergency_vehicle_plugin_container = ComposableNodeContainer(
163 package=
'carma_ros2_utils',
164 name=
'carma_approaching_emergency_vehicle_plugin_container',
165 executable=
'carma_component_container_mt',
166 namespace=GetCurrentNamespace(),
167 composable_node_descriptions=[
170 package=
'approaching_emergency_vehicle_plugin',
171 plugin=
'approaching_emergency_vehicle_plugin::ApproachingEmergencyVehiclePlugin',
172 name=
'approaching_emergency_vehicle_plugin',
174 {
'use_intra_process_comms':
True},
175 {
'--log-level' : GetLogLevel(
'approaching_emergency_vehicle_plugin', env_log_levels) }
178 (
"semantic_map", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/semantic_map" ] ),
179 (
"map_update", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/map_update" ] ),
180 (
"roadway_objects", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/roadway_objects" ] ),
181 (
"incoming_spat", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_spat" ] ),
182 (
"plugin_discovery", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugin_discovery" ] ),
183 (
"route", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/route" ] ),
184 (
"state", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/state" ] ),
185 (
"approaching_erv_status", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/approaching_erv_status" ] ),
186 (
"hazard_light_status", [ EnvironmentVariable(
'CARMA_INTR_NS', default_value=
''),
"/hazard_light_status" ] ),
187 (
"current_velocity", [ EnvironmentVariable(
'CARMA_INTR_NS', default_value=
''),
"/vehicle/twist" ] ),
188 (
"incoming_bsm", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_bsm" ] ),
189 (
"georeference", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/map_param_loader/georeference" ] ),
190 (
"route_state", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/route_state" ] ),
191 (
"outgoing_emergency_vehicle_response", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/outgoing_emergency_vehicle_response" ] ),
192 (
"incoming_emergency_vehicle_ack", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_emergency_vehicle_ack" ])
195 approaching_emergency_vehicle_plugin_param_file,
196 vehicle_characteristics_param_file,
197 vehicle_config_param_file
203 carma_stop_and_wait_plugin_container = ComposableNodeContainer(
204 package=
'carma_ros2_utils',
205 name=
'carma_stop_and_wait_plugin_container',
206 executable=
'carma_component_container_mt',
207 namespace=GetCurrentNamespace(),
208 composable_node_descriptions=[
211 package=
'stop_and_wait_plugin',
212 plugin=
'stop_and_wait_plugin::StopandWaitNode',
213 name=
'stop_and_wait_plugin',
215 {
'use_intra_process_comms':
True},
216 {
'--log-level' : GetLogLevel(
'stop_and_wait_plugin', env_log_levels) }
219 (
"semantic_map", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/semantic_map" ] ),
220 (
"map_update", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/map_update" ] ),
221 (
"roadway_objects", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/roadway_objects" ] ),
222 (
"incoming_spat", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_spat" ] ),
223 (
"plugin_discovery", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugin_discovery" ] ),
224 (
"route", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/route" ] ),
227 stop_and_wait_plugin_param_file,
228 vehicle_config_param_file
234 carma_sci_strategic_plugin_container = ComposableNodeContainer(
235 package=
'carma_ros2_utils',
236 name=
'carma_sci_strategic_plugin_container',
237 executable=
'carma_component_container_mt',
238 namespace=GetCurrentNamespace(),
239 composable_node_descriptions=[
241 package=
'sci_strategic_plugin',
242 plugin=
'sci_strategic_plugin::SCIStrategicPlugin',
243 name=
'sci_strategic_plugin',
245 {
'use_intra_process_comms':
True},
246 {
'--log-level' : GetLogLevel(
'sci_strategic_plugin', env_log_levels) }
249 (
"semantic_map", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/semantic_map" ] ),
250 (
"map_update", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/map_update" ] ),
251 (
"roadway_objects", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/roadway_objects" ] ),
252 (
"incoming_spat", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_spat" ] ),
253 (
"plugin_discovery", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugin_discovery" ] ),
254 (
"route", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/route" ] ),
255 (
"maneuver_plan", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/final_maneuver_plan" ] ),
256 (
"outgoing_mobility_operation", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/outgoing_mobility_operation" ] ),
257 (
"incoming_mobility_operation", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_mobility_operation" ] ),
258 (
"bsm_outbound", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/bsm_outbound" ] ),
259 (
"current_pose", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/current_pose" ] ),
262 sci_strategic_plugin_file_path,
263 vehicle_config_param_file
269 carma_lci_strategic_plugin_container = ComposableNodeContainer(
270 package=
'carma_ros2_utils',
271 name=
'carma_lci_strategic_plugin_container',
272 executable=
'carma_component_container_mt',
273 namespace=GetCurrentNamespace(),
274 composable_node_descriptions=[
276 package=
'lci_strategic_plugin',
277 plugin=
'lci_strategic_plugin::LCIStrategicPlugin',
278 name=
'lci_strategic_plugin',
280 {
'use_intra_process_comms':
True},
281 {
'--log-level' : GetLogLevel(
'lci_strategic_plugin', env_log_levels) }
284 (
"semantic_map", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/semantic_map" ] ),
285 (
"map_update", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/map_update" ] ),
286 (
"roadway_objects", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/roadway_objects" ] ),
287 (
"incoming_spat", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_spat" ] ),
288 (
"plugin_discovery", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugin_discovery" ] ),
289 (
"route", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/route" ] ),
290 (
"maneuver_plan", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/final_maneuver_plan" ] ),
291 (
"outgoing_mobility_operation", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/outgoing_mobility_operation" ] ),
292 (
"incoming_mobility_operation", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_mobility_operation" ] ),
293 (
"bsm_outbound", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/bsm_outbound" ] ),
296 lci_strategic_plugin_file_path,
297 vehicle_config_param_file,
298 unique_vehicle_calibration_params
304 carma_stop_controlled_intersection_tactical_plugin_container = ComposableNodeContainer(
305 package=
'carma_ros2_utils',
306 name=
'carma_stop_controlled_intersection_tactical_plugin_container',
307 executable=
'carma_component_container_mt',
308 namespace=GetCurrentNamespace(),
309 composable_node_descriptions=[
311 package=
'stop_controlled_intersection_tactical_plugin',
312 plugin=
'stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin',
313 name=
'stop_controlled_intersection_tactical_plugin',
315 {
'use_intra_process_comms':
True},
316 {
'--log-level' : GetLogLevel(
'stop_controlled_intersection_tactical_plugin', env_log_levels) }
319 (
"semantic_map", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/semantic_map" ] ),
320 (
"map_update", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/map_update" ] ),
321 (
"roadway_objects", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/roadway_objects" ] ),
322 (
"incoming_spat", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_spat" ] ),
323 (
"plugin_discovery", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugin_discovery" ] ),
324 (
"route", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/route" ] )
327 stop_controlled_intersection_tactical_plugin_file_path,
328 vehicle_config_param_file
334 carma_cooperative_lanechange_plugins_container = ComposableNodeContainer(
335 package=
'carma_ros2_utils',
336 name=
'carma_cooperative_lanechange_plugins_container',
337 executable=
'carma_component_container_mt',
338 namespace=GetCurrentNamespace(),
339 composable_node_descriptions=[
341 package=
'cooperative_lanechange',
342 plugin=
'cooperative_lanechange::CooperativeLaneChangePlugin',
343 name=
'cooperative_lanechange',
345 {
'use_intra_process_comms':
True},
346 {
'--log-level' : GetLogLevel(
'cooperative_lanechange', env_log_levels) }
349 (
"semantic_map", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/semantic_map" ] ),
350 (
"map_update", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/map_update" ] ),
351 (
"roadway_objects", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/roadway_objects" ] ),
352 (
"incoming_spat", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_spat" ] ),
353 (
"plugin_discovery", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugin_discovery" ] ),
354 (
"route", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/route" ] ),
355 (
"current_velocity", [ EnvironmentVariable(
'CARMA_INTR_NS', default_value=
''),
"/vehicle/twist" ] ),
356 (
"cooperative_lane_change_status", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/cooperative_lane_change_status" ] ),
357 (
"bsm_outbound", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/bsm_outbound" ] ),
358 (
"outgoing_mobility_request", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/outgoing_mobility_request" ] ),
359 (
"incoming_mobility_response", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_mobility_response" ] ),
360 (
"georeference", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/map_param_loader/georeference" ] ),
361 (
"current_pose", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/current_pose" ] )
364 cooperative_lanechange_param_file,
365 vehicle_characteristics_param_file,
366 vehicle_config_param_file
372 carma_yield_plugin_container = ComposableNodeContainer(
373 package=
'carma_ros2_utils',
374 name=
'carma_yield_plugin_container',
375 executable=
'carma_component_container_mt',
376 namespace=GetCurrentNamespace(),
377 composable_node_descriptions=[
379 package=
'yield_plugin',
380 plugin=
'yield_plugin::YieldPluginNode',
383 {
'use_intra_process_comms':
True},
384 {
'--log-level' : GetLogLevel(
'yield_plugin', env_log_levels) }
387 (
"semantic_map", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/semantic_map" ] ),
388 (
"map_update", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/map_update" ] ),
389 (
"external_object_predictions", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/external_object_predictions" ] ),
390 (
"incoming_spat", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_spat" ] ),
391 (
"plugin_discovery", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugin_discovery" ] ),
392 (
"route", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/route" ] ),
393 (
"outgoing_mobility_response", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/outgoing_mobility_response" ] ),
394 (
"incoming_mobility_request", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_mobility_request" ] ),
395 (
"cooperative_lane_change_status", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/cooperative_lane_change_status" ] ),
396 (
"georeference", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/map_param_loader/georeference"]),
397 (
"bsm_outbound", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/bsm_outbound" ] ),
400 yield_plugin_file_path,
401 vehicle_config_param_file
407 carma_light_controlled_intersection_plugins_container = ComposableNodeContainer(
408 package=
'carma_ros2_utils',
409 name=
'carma_light_controlled_intersection_plugins_container',
410 executable=
'carma_component_container_mt',
411 namespace=GetCurrentNamespace(),
412 composable_node_descriptions=[
414 package=
'light_controlled_intersection_tactical_plugin',
415 plugin=
'light_controlled_intersection_tactical_plugin::LightControlledIntersectionTransitPluginNode',
416 name=
'light_controlled_intersection_tactical_plugin',
418 {
'use_intra_process_comms':
True},
419 {
'--log-level' : GetLogLevel(
'light_controlled_intersection_tactical_plugin', env_log_levels) }
422 (
"semantic_map", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/semantic_map" ] ),
423 (
"map_update", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/map_update" ] ),
424 (
"roadway_objects", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/roadway_objects" ] ),
425 (
"incoming_spat", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_spat" ] ),
426 (
"plugin_discovery", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugin_discovery" ] ),
427 (
"route", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/route" ] )
430 vehicle_config_param_file,
431 vehicle_characteristics_param_file,
432 light_controlled_intersection_tactical_plugin_param_file
438 carma_pure_pursuit_wrapper_container = ComposableNodeContainer(
439 package=
'carma_ros2_utils',
440 name=
'carma_pure_pursuit_wrapper_container',
441 executable=
'carma_component_container_mt',
442 namespace=GetCurrentNamespace(),
443 composable_node_descriptions=[
445 package=
'pure_pursuit_wrapper',
446 plugin=
'pure_pursuit_wrapper::PurePursuitWrapperNode',
447 name=
'pure_pursuit_wrapper',
449 {
'use_intra_process_comms':
True},
450 {
'--log-level' : GetLogLevel(
'pure_pursuit_wrapper', env_log_levels) }
453 (
"plugin_discovery", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugin_discovery" ] ),
454 (
"ctrl_raw", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/ctrl_raw" ] ),
455 (
"pure_pursuit_wrapper/plan_trajectory", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugins/pure_pursuit/plan_trajectory" ] ),
456 (
"current_pose", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/current_pose" ] ),
457 (
"vehicle/twist", [ EnvironmentVariable(
'CARMA_INTR_NS', default_value=
''),
"/vehicle/twist" ] ),
460 vehicle_characteristics_param_file,
461 vehicle_config_param_file,
462 pure_pursuit_tuning_parameters
468 trajectory_follower_container = ComposableNodeContainer(
469 package=
'carma_ros2_utils',
470 name=
'trajectory_follower_container',
471 executable=
'carma_component_container_mt',
472 namespace=GetCurrentNamespace(),
473 composable_node_descriptions=[
475 package=
'trajectory_follower_nodes',
476 plugin=
'autoware::motion::control::trajectory_follower_nodes::LatLonMuxer',
477 name=
'latlon_muxer_node',
479 {
'use_intra_process_comms':
False},
480 {
'--log-level' : GetLogLevel(
'latlon_muxer', env_log_levels) }
483 (
"input/lateral/control_cmd",
"trajectory_follower/lateral/control_cmd"),
484 (
"input/longitudinal/control_cmd",
"trajectory_follower/longitudinal/control_cmd"),
485 (
"output/control_cmd",
"trajectory_follower/control_cmd")
488 {
'timeout_thr_sec':0.5}
492 package=
'trajectory_follower_nodes',
493 plugin=
'autoware::motion::control::trajectory_follower_nodes::LateralController',
494 name=
'lateral_controller_node',
496 {
'use_intra_process_comms':
True},
497 {
'--log-level' : GetLogLevel(
'lateral_controller', env_log_levels) }
500 (
"output/lateral/control_cmd",
"trajectory_follower/lateral/control_cmd"),
501 (
"input/current_kinematic_state",
"trajectory_follower/current_kinematic_state"),
502 (
"input/reference_trajectory",
"trajectory_follower/reference_trajectory" )
505 [vehicle_calibration_dir,
"/trajectory_follower/lateral_controller_defaults.yaml"]
509 package=
'trajectory_follower_nodes',
510 plugin=
'autoware::motion::control::trajectory_follower_nodes::LongitudinalController',
511 name=
'longitudinal_controller_node',
513 {
'use_intra_process_comms':
False},
514 {
'--log-level' : GetLogLevel(
'longitudinal_controller', env_log_levels) }
517 (
"output/longitudinal/control_cmd",
"trajectory_follower/longitudinal/control_cmd"),
518 (
"input/current_trajectory",
"trajectory_follower/reference_trajectory"),
519 (
"input/current_state",
"trajectory_follower/current_kinematic_state")
522 [vehicle_calibration_dir,
"/trajectory_follower/longitudinal_controller_defaults.yaml"]
527 carma_trajectory_follower_wrapper_container = ComposableNodeContainer(
528 package=
'carma_ros2_utils',
529 name=
'carma_trajectory_follower_wrapper_container',
530 executable=
'carma_component_container_mt',
531 namespace=GetCurrentNamespace(),
532 composable_node_descriptions=[
534 package=
'trajectory_follower_wrapper',
535 plugin=
'trajectory_follower_wrapper::TrajectoryFollowerWrapperNode',
536 name=
'trajectory_follower_wrapper',
538 {
'use_intra_process_comms':
True},
539 {
'--log-level' : GetLogLevel(
'trajectory_follower_wrapper', env_log_levels) }
542 (
"plugin_discovery", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugin_discovery" ] ),
543 (
"ctrl_raw", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/ctrl_raw" ] ),
544 (
"trajectory_follower_wrapper/plan_trajectory", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugins/trajectory_follower_wrapper/plan_trajectory" ] ),
545 (
"current_pose", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/current_pose" ] ),
546 (
"vehicle/twist", [ EnvironmentVariable(
'CARMA_INTR_NS', default_value=
''),
"/vehicle/twist" ] ),
549 vehicle_characteristics_param_file,
550 trajectory_follower_wrapper_param_file
556 platooning_strategic_plugin_container = ComposableNodeContainer(
557 package=
'carma_ros2_utils',
558 name=
'platooning_strategic_plugin_container',
559 executable=
'carma_component_container_mt',
560 namespace=GetCurrentNamespace(),
561 composable_node_descriptions=[
563 package=
'platooning_strategic_ihp',
564 plugin=
'platooning_strategic_ihp::Node',
565 name=
'platooning_strategic_ihp_node',
567 {
'use_intra_process_comms':
True},
568 {
'--log-level' : GetLogLevel(
'platooning_strategic_ihp', env_log_levels) }
571 (
"semantic_map", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/semantic_map" ] ),
572 (
"map_update", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/map_update" ] ),
573 (
"roadway_objects", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/roadway_objects" ] ),
574 (
"georeference", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/map_param_loader/georeference" ] ),
575 (
"outgoing_mobility_response", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/outgoing_mobility_response" ] ),
576 (
"outgoing_mobility_request", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/outgoing_mobility_request" ] ),
577 (
"outgoing_mobility_operation", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/outgoing_mobility_operation" ] ),
578 (
"incoming_mobility_request", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_mobility_request" ] ),
579 (
"incoming_mobility_response", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_mobility_response" ] ),
580 (
"incoming_mobility_operation", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_mobility_operation" ] ),
581 (
"incoming_spat", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_spat" ] ),
582 (
"twist_raw", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/twist_raw" ] ),
583 (
"platoon_info", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/platoon_info" ] ),
584 (
"plugin_discovery", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugin_discovery" ] ),
585 (
"route", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/route" ] ),
586 (
"current_velocity", [ EnvironmentVariable(
'CARMA_INTR_NS', default_value=
''),
"/vehicle/twist" ] ),
587 (
"current_pose", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/current_pose" ] ),
590 platooning_strategic_ihp_param_file,
591 vehicle_config_param_file
597 platooning_tactical_plugin_container = ComposableNodeContainer(
598 package=
'carma_ros2_utils',
599 name=
'platooning_tactical_plugin_container',
600 executable=
'carma_component_container_mt',
601 namespace=GetCurrentNamespace(),
602 composable_node_descriptions=[
604 package=
'platooning_tactical_plugin',
605 plugin=
'platooning_tactical_plugin::Node',
606 name=
'platooning_tactical_plugin_node',
608 {
'use_intra_process_comms':
True},
609 {
'--log-level' : GetLogLevel(
'platooning_tactical_plugin', env_log_levels) }
612 (
"semantic_map", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/semantic_map" ] ),
613 (
"map_update", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/map_update" ] ),
614 (
"roadway_objects", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/roadway_objects" ] ),
615 (
"georeference", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/map_param_loader/georeference" ] ),
616 (
"incoming_spat", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_spat" ] ),
617 (
"plugin_discovery", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugin_discovery" ] ),
618 (
"route", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/route" ] ),
620 parameters=[ platoon_tactical_ihp_param_file, vehicle_config_param_file ]
625 platooning_control_plugin_container = ComposableNodeContainer(
626 package=
'carma_ros2_utils',
627 name=
'platooning_control_container',
628 executable=
'carma_component_container_mt',
629 namespace=GetCurrentNamespace(),
630 composable_node_descriptions=[
632 package=
'platooning_control',
633 plugin=
'platooning_control::PlatooningControlPlugin',
634 name=
'platooning_control',
636 {
'use_intra_process_comms':
True},
637 {
'--log-level' : GetLogLevel(
'platooning_control_plugin', env_log_levels) }
640 (
"plugin_discovery", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugin_discovery" ] ),
641 (
"ctrl_raw", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/ctrl_raw" ] ),
642 (
"twist_raw", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/twist_raw" ] ),
643 (
"platooning_control/plan_trajectory", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugins/platooning_control/plan_trajectory" ] ),
644 (
"current_pose", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/current_pose" ] ),
645 (
"vehicle/twist", [ EnvironmentVariable(
'CARMA_INTR_NS', default_value=
''),
"/vehicle/twist" ] ),
647 parameters=[ platooning_control_param_file, vehicle_config_param_file, unique_vehicle_calibration_params ]
652 carma_stop_and_dwell_strategic_plugin_container = ComposableNodeContainer(
653 package=
'carma_ros2_utils',
654 name=
'carma_stop_and_dwell_strategic_plugin_container',
655 executable=
'carma_component_container_mt',
656 namespace=GetCurrentNamespace(),
657 composable_node_descriptions=[
659 package=
'stop_and_dwell_strategic_plugin',
660 plugin=
'stop_and_dwell_strategic_plugin::StopAndDwellStrategicPlugin',
661 name=
'stop_and_dwell_strategic_plugin',
663 {
'use_intra_process_comms':
True},
664 {
'--log-level' : GetLogLevel(
'stop_and_dwell_strategic_plugin', env_log_levels) }
667 (
"semantic_map", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/semantic_map" ] ),
668 (
"map_update", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/map_update" ] ),
669 (
"roadway_objects", [ EnvironmentVariable(
'CARMA_ENV_NS', default_value=
''),
"/roadway_objects" ] ),
670 (
"incoming_spat", [ EnvironmentVariable(
'CARMA_MSG_NS', default_value=
''),
"/incoming_spat" ] ),
671 (
"plugin_discovery", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/plugin_discovery" ] ),
672 (
"route", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/route" ] ),
673 (
"maneuver_plan", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/final_maneuver_plan" ] ),
674 (
"state", [ EnvironmentVariable(
'CARMA_GUIDE_NS', default_value=
''),
"/state" ] ),
675 (
"current_pose", [ EnvironmentVariable(
'CARMA_LOCZ_NS', default_value=
''),
"/current_pose" ] ),
678 stop_and_dwell_strategic_plugin_container_file_path,
679 vehicle_config_param_file
685 intersection_transit_maneuvering_container = ComposableNodeContainer(
686 package=
'carma_ros2_utils',
687 name=
'intersection_transit_maneuvering_container',
688 executable=
'carma_component_container_mt',
689 namespace=GetCurrentNamespace(),
690 composable_node_descriptions=[
692 package=
'intersection_transit_maneuvering',
693 plugin=
'intersection_transit_maneuvering::IntersectionTransitManeuveringNode',
694 name=
'intersection_transit_maneuvering',
696 {
'use_intra_process_comms':
True},
697 {
'--log-level' : GetLogLevel(
'intersection_transit_maneuvering', env_log_levels) }
701 vehicle_config_param_file
707 return LaunchDescription([
708 carma_inlanecruising_plugin_container,
709 carma_route_following_plugin_container,
710 carma_approaching_emergency_vehicle_plugin_container,
711 carma_stop_and_wait_plugin_container,
712 carma_sci_strategic_plugin_container,
713 carma_stop_and_dwell_strategic_plugin_container,
714 carma_lci_strategic_plugin_container,
715 carma_stop_controlled_intersection_tactical_plugin_container,
716 carma_cooperative_lanechange_plugins_container,
717 carma_yield_plugin_container,
718 carma_light_controlled_intersection_plugins_container,
719 carma_pure_pursuit_wrapper_container,
720 carma_trajectory_follower_wrapper_container,
722 platooning_tactical_plugin_container,
723 platooning_control_plugin_container,
724 intersection_transit_maneuvering_container,
725 trajectory_follower_container
def generate_launch_description()