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

Functions

def generate_launch_description ()
 

Function Documentation

◆ generate_launch_description()

def message.generate_launch_description ( )
Launch V2X subsystem nodes.

Definition at line 38 of file message.launch.py.

39
40 """
41 Launch V2X subsystem nodes.
42 """
43
44 env_log_levels = EnvironmentVariable('CARMA_ROS_LOGGING_CONFIG', default_value='{ "default_level" : "WARN" }')
45
46 subsystem_controller_default_param_file = os.path.join(
47 get_package_share_directory('subsystem_controllers'), 'config/v2x_controller_config.yaml')
48
49 mobilitypath_publisher_param_file = os.path.join(
50 get_package_share_directory('mobilitypath_publisher'), 'config/parameters.yaml')
51
52 bsm_generator_param_file = os.path.join(
53 get_package_share_directory('bsm_generator'), 'config/parameters.yaml')
54
55 vehicle_characteristics_param_file = LaunchConfiguration('vehicle_characteristics_param_file')
56 declare_vehicle_characteristics_param_file_arg = DeclareLaunchArgument(
57 name = 'vehicle_characteristics_param_file',
58 default_value = "/opt/carma/vehicle/calibration/identifiers/UniqueVehicleParams.yaml",
59 description = "Path to file containing unique vehicle calibrations"
60 )
61
62
63 vehicle_config_param_file = LaunchConfiguration('vehicle_config_param_file')
64 declare_vehicle_config_param_file_arg = DeclareLaunchArgument(
65 name = 'vehicle_config_param_file',
66 default_value = "/opt/carma/vehicle/config/VehicleConfigParams.yaml",
67 description = "Path to file contain vehicle configuration parameters"
68 )
69
70 subsystem_controller_param_file = LaunchConfiguration('subsystem_controller_param_file')
71 declare_subsystem_controller_param_file_arg = DeclareLaunchArgument(
72 name = 'subsystem_controller_param_file',
73 default_value = subsystem_controller_default_param_file,
74 description = "Path to file containing override parameters for the subsystem controller"
75 )
76
77 # Declare enable_opening_tunnels
78 enable_opening_tunnels = LaunchConfiguration('enable_opening_tunnels')
79 declare_enable_opening_tunnels = DeclareLaunchArgument(
80 name = 'enable_opening_tunnels',
81 default_value= 'True',
82 description='Flag to enable opening http tunnesl to CARMA Cloud'
83 )
84
85 carma_cloud_client_param_file = os.path.join(
86 get_package_share_directory('carma_cloud_client'), 'config/parameters.yaml')
87
88 use_sim_time = LaunchConfiguration('use_sim_time')
89 declare_use_sim_time_arg = DeclareLaunchArgument(
90 name = 'use_sim_time',
91 default_value = "False",
92 description = "True if simulation mode is on"
93 )
94
95 # Nodes
96 carma_v2x_container = ComposableNodeContainer(
97 package='carma_ros2_utils',
98 name='carma_v2x_container',
99 executable='carma_component_container_mt',
100 namespace=GetCurrentNamespace(),
101 composable_node_descriptions=[
102
103 ComposableNode(
104 package='mobilitypath_publisher',
105 plugin='mobilitypath_publisher::MobilityPathPublication',
106 name='mobilitypath_publisher_node',
107 extra_arguments=[
108 {'use_intra_process_comms': True},
109 {'--log-level' : GetLogLevel('mobilitypath_publisher', env_log_levels) }
110 ],
111 remappings=[
112 ("plan_trajectory", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/plan_trajectory" ] ),
113 ("guidance_state", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/state" ] ),
114 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] ),
115 ("mobility_path_msg", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_mobility_path" ] )
116 ],
117 parameters=[
118 mobilitypath_publisher_param_file,
119 vehicle_characteristics_param_file,
120 vehicle_config_param_file
121 ]
122 ),
123 ComposableNode(
124 package='bsm_generator',
125 plugin='bsm_generator::BSMGenerator',
126 name='bsm_generator_node',
127 extra_arguments=[
128 {'use_intra_process_comms': True},
129 {'--log-level' : GetLogLevel('bsm_generator', env_log_levels) }
130 ],
131 remappings=[
132 ("velocity_accel_cov", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/velocity_accel_cov" ] ),
133 ("ekf_twist", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle/twist" ] ),
134 ("imu_raw", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/imu_raw" ] ),
135 ("transmission_state", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/can/transmission_state" ] ),
136 ("brake_position", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/can/brake_position" ] ),
137 ("steering_wheel_angle", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/can/steering_wheel_angle" ] ),
138 ("gnss_fix_fused", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/gnss_fix_fused" ] ),
139 ("pose", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] ),
140 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] )
141 ],
142 parameters=[
143 bsm_generator_param_file,
144 vehicle_characteristics_param_file,
145 vehicle_config_param_file
146 ]
147 ),
148 ComposableNode(
149 package='cpp_message',
150 plugin='cpp_message::Node',
151 name='cpp_message_node',
152 extra_arguments=[
153 {'use_intra_process_comms': True},
154 {'--log-level' : GetLogLevel('cpp_message', env_log_levels) }
155 ],
156 remappings=[
157 ("inbound_binary_msg", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/comms/inbound_binary_msg" ] ),
158 ("outbound_binary_msg", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/comms/outbound_binary_msg" ] ),
159 ],
160 parameters=[
161 vehicle_config_param_file
162 ]
163 ),
164 ComposableNode(
165 package='j2735_convertor',
166 plugin='j2735_convertor::Node',
167 name='j2735_convertor_node',
168 extra_arguments=[
169 {'use_intra_process_comms': True},
170 {'--log-level' : GetLogLevel('j2735_convertor', env_log_levels) }
171 ],
172 remappings=[
173 ("outgoing_bsm", "bsm_outbound" )
174 ],
175 parameters=[
176 vehicle_config_param_file
177 ]
178 ),
179 ComposableNode(
180 package='carma_cloud_client',
181 plugin='carma_cloud_client::CarmaCloudClient',
182 name='carma_cloud_client_node',
183 extra_arguments=[
184 {'use_intra_process_comms': True},
185 {'--log-level' : GetLogLevel('carma_cloud_client', env_log_levels) }
186 ],
187 remappings=[
188 ("incoming_geofence_control", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_geofence_control" ] ),
189 ],
190 parameters = [
191 vehicle_config_param_file, carma_cloud_client_param_file
192 ]
193
194 ),
195 ]
196 )
197
198 # subsystem_controller which orchestrates the lifecycle of this subsystem's components
199 subsystem_controller = Node(
200 package='subsystem_controllers',
201 name='v2x_controller',
202 executable='v2x_controller',
203 parameters=[
204 subsystem_controller_default_param_file,
205 subsystem_controller_param_file,
206 {"use_sim_time" : use_sim_time}], # Default file is loaded first followed by config file
207 on_exit= Shutdown(), # Mark the subsystem controller as required
208 arguments=['--ros-args', '--log-level', GetLogLevel('subsystem_controllers', env_log_levels)]
209 )
210
211 # Info needed for opening the tunnels
212 # TODO: Investigate if this can be further cleaned up
213 REMOTE_USER="ubuntu"
214 REMOTE_ADDR="www.carma-cloud.com"
215 KEY_FILE="carma-cloud-test-1.pem"
216 HOST_PORT="33333" # This port is forwarded to remote host (carma-cloud)
217 REMOTE_PORT="10001" # This port is forwarded to local host
218 param_launch_path = os.path.join(
219 get_package_share_directory('carma_cloud_client'), 'launch/scripts')
220
221 script = param_launch_path + '/open_tunnels.sh'
222
223 subprocess.check_call(['chmod','u+x', script])
224
225 key_path = "/opt/carma/vehicle/calibration/cloud_permission"
226
227 keyfile = key_path + '/' + KEY_FILE
228
229 subprocess.check_call(['sudo','chmod','400', keyfile])
230
231
232 open_tunnels_action = ExecuteProcess(
233
234 condition=IfCondition(enable_opening_tunnels),
235 cmd = ['sudo', script, '-u', REMOTE_USER, '-a', REMOTE_ADDR, '-k', keyfile, '-p', REMOTE_PORT, '-r', HOST_PORT],
236 output = 'screen'
237 )
238
239
240 return LaunchDescription([
241 declare_vehicle_config_param_file_arg,
242 declare_use_sim_time_arg,
243 declare_vehicle_characteristics_param_file_arg,
244 declare_subsystem_controller_param_file_arg,
245 declare_enable_opening_tunnels,
246 open_tunnels_action,
247 carma_v2x_container,
248 subsystem_controller
249 ])
250
251
def generate_launch_description()