32    """
   33    Launch the subsystem controller for the hardware interface subsystem.
   34    The actual drivers will not be launched in this file and will instead be launched in the carma-config.
   35    """
   36 
   37    vehicle_config_param_file = LaunchConfiguration('vehicle_config_param_file')
   38    declare_vehicle_config_param_file_arg = DeclareLaunchArgument(
   39        name = 'vehicle_config_param_file',
   40        default_value = "/opt/carma/vehicle/config/VehicleConfigParams.yaml",
   41        description = "Path to file contain vehicle configuration parameters"
   42    )
   43 
   44    use_sim_time = LaunchConfiguration('use_sim_time')
   45    declare_use_sim_time_arg = DeclareLaunchArgument(
   46        name = 'use_sim_time',
   47        default_value = "False",
   48        description = "True if simulation mode is on"
   49    )
   50 
   51 
   52    env_log_levels = EnvironmentVariable('CARMA_ROS_LOGGING_CONFIG', default_value='{ "default_level" : "WARN" }')
   53 
   54    subsystem_controller_default_param_file = os.path.join(
   55        get_package_share_directory('subsystem_controllers'), 'config/drivers_controller_config.yaml')
   56 
   57    subsystem_controller_param_file = LaunchConfiguration('subsystem_controller_param_file')
   58    declare_subsystem_controller_param_file_arg = DeclareLaunchArgument(
   59        name = 'subsystem_controller_param_file',
   60        default_value = subsystem_controller_default_param_file,
   61        description = "Path to file containing override parameters for the subsystem controller"
   62    )
   63 
   64    vehicle_config_dir = LaunchConfiguration('vehicle_config_dir')
   65    declare_vehicle_config_dir_arg = DeclareLaunchArgument(
   66        name = 'vehicle_config_dir',
   67        default_value = "/opt/carma/vehicle/config",
   68        description = "Path to vehicle configuration directory populated by carma-config"
   69    )
   70 
   71    
   72    
   73    global_params_override_file = LaunchConfiguration('global_params_override_file')
   74    declare_global_params_override_file_arg = DeclareLaunchArgument(
   75        name = 'global_params_override_file',
   76        default_value = [vehicle_config_dir, "/GlobalParamsOverride.yaml"],
   77        description = "Path to global file containing the parameters overwrite"
   78    )
   79 
   80    lightbar_manager_param_file = os.path.join(
   81        get_package_share_directory('lightbar_manager'), 'config/params.yaml')
   82 
   83    lightbar_manager_container = ComposableNodeContainer(
   84        package='carma_ros2_utils', 
   85        name='lightbar_manager_container',
   86        executable='lifecycle_component_wrapper_mt',
   87        namespace=GetCurrentNamespace(),
   88        composable_node_descriptions=[
   89            ComposableNode(
   90                package='lightbar_manager',
   91                plugin='lightbar_manager::LightBarManager',
   92                name='lightbar_manager',
   93                extra_arguments=[
   94                    {'use_intra_process_comms': True},
   95                    {'--log-level' : GetLogLevel('lightbar_manager', env_log_levels) },
   96                    {'is_lifecycle_node': True} 
   97                ],
   98                remappings=[
   99                    ("state", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/state" ] ),
  100                    ("set_lights", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/lightbar/set_lights" ] )
  101                ],
  102                parameters=[
  103                    lightbar_manager_param_file,
  104                    vehicle_config_param_file,
  105                    global_params_override_file
  106                ]
  107            )
  108        ]
  109    )
  110 
  111    
  112    subsystem_controller = Node(
  113        package='subsystem_controllers',
  114        name='drivers_controller',
  115        executable='drivers_controller',
  116        parameters=[
  117            subsystem_controller_default_param_file,
  118            subsystem_controller_param_file,
  119            {"use_sim_time" : use_sim_time}],
  120        on_exit= Shutdown(), 
  121        arguments=['--ros-args', '--log-level', GetLogLevel('subsystem_controllers', env_log_levels)]
  122    )
  123 
  124    return LaunchDescription([
  125        declare_subsystem_controller_param_file_arg,
  126        declare_vehicle_config_param_file_arg,
  127        declare_vehicle_config_dir_arg,
  128        declare_global_params_override_file_arg,
  129        declare_use_sim_time_arg,
  130        lightbar_manager_container,
  131        subsystem_controller,
  132    ])
def generate_launch_description()