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

Functions

def generate_launch_description ()
 

Function Documentation

◆ generate_launch_description()

def drivers.generate_launch_description ( )
Launch the subsystem controller for the hardware interface subsystem.
The actual drivers will not be launched in this file and will instead be launched in the carma-config.

Definition at line 31 of file drivers.launch.py.

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 lightbar_manager_param_file = os.path.join(
65 get_package_share_directory('lightbar_manager'), 'config/params.yaml')
66
67 lightbar_manager_container = ComposableNodeContainer(
68 package='carma_ros2_utils', # rclcpp_components
69 name='lightbar_manager_container',
70 executable='lifecycle_component_wrapper_mt',
71 namespace=GetCurrentNamespace(),
72 composable_node_descriptions=[
73 ComposableNode(
74 package='lightbar_manager',
75 plugin='lightbar_manager::LightBarManager',
76 name='lightbar_manager',
77 extra_arguments=[
78 {'use_intra_process_comms': True},
79 {'--log-level' : GetLogLevel('lightbar_manager', env_log_levels) },
80 {'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
81 ],
82 remappings=[
83 ("state", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/state" ] ),
84 ("set_lights", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/lightbar/set_lights" ] )
85 ],
86 parameters=[
87 lightbar_manager_param_file,
88 vehicle_config_param_file
89 ]
90 )
91 ]
92 )
93
94 # subsystem_controller which orchestrates the lifecycle of this subsystem's components
95 subsystem_controller = Node(
96 package='subsystem_controllers',
97 name='drivers_controller',
98 executable='drivers_controller',
99 parameters=[
100 subsystem_controller_default_param_file,
101 subsystem_controller_param_file,
102 {"use_sim_time" : use_sim_time}],
103 on_exit= Shutdown(), # Mark the subsystem controller as required
104 arguments=['--ros-args', '--log-level', GetLogLevel('subsystem_controllers', env_log_levels)]
105 )
106
107 return LaunchDescription([
108 declare_subsystem_controller_param_file_arg,
109 declare_vehicle_config_param_file_arg,
110 declare_use_sim_time_arg,
111 lightbar_manager_container,
112 subsystem_controller,
113 ])
def generate_launch_description()