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.
guidance.launch.py
Go to the documentation of this file.
1# Copyright (C) 2022 LEIDOS.
2#
3# Licensed under the Apache License, Version 2.0 (the "License");
4# you may not use this file except in compliance with the License.
5# You may obtain a copy of the License at
6#
7# http://www.apache.org/licenses/LICENSE-2.0
8#
9# Unless required by applicable law or agreed to in writing, software
10# distributed under the License is distributed on an "AS IS" BASIS,
11# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12# See the License for the specific language governing permissions and
13# limitations under the License.
14
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 launch.substitutions import ThisLaunchFileDir
23from carma_ros2_utils.launch.get_log_level import GetLogLevel
24from carma_ros2_utils.launch.get_current_namespace import GetCurrentNamespace
25from launch.substitutions import LaunchConfiguration
26
27import os
28
29from launch.actions import IncludeLaunchDescription
30from launch.launch_description_sources import PythonLaunchDescriptionSource
31from launch.actions import GroupAction
32from launch_ros.actions import set_remap
33from launch.actions import DeclareLaunchArgument
34from launch_ros.actions import PushRosNamespace
35
36
37# Launch file for launching the nodes in the CARMA guidance stack
38
40
41 route_file_folder = LaunchConfiguration('route_file_folder')
42 vehicle_calibration_dir = LaunchConfiguration('vehicle_calibration_dir')
43 vehicle_characteristics_param_file = LaunchConfiguration('vehicle_characteristics_param_file')
44 enable_guidance_plugin_validator = LaunchConfiguration('enable_guidance_plugin_validator')
45 strategic_plugins_to_validate = LaunchConfiguration('strategic_plugins_to_validate')
46 tactical_plugins_to_validate = LaunchConfiguration('tactical_plugins_to_validate')
47 control_plugins_to_validate = LaunchConfiguration('control_plugins_to_validate')
48 vehicle_config_dir = LaunchConfiguration('vehicle_config_dir')
49 vehicle_config_param_file = LaunchConfiguration('vehicle_config_param_file')
50 declare_vehicle_config_param_file_arg = DeclareLaunchArgument(
51 name = 'vehicle_config_param_file',
52 default_value = "/opt/carma/vehicle/config/VehicleConfigParams.yaml",
53 description = "Path to file contain vehicle configuration parameters"
54 )
55
56 use_sim_time = LaunchConfiguration('use_sim_time')
57 declare_use_sim_time_arg = DeclareLaunchArgument(
58 name = 'use_sim_time',
59 default_value = "False",
60 description = "True if simulation mode is on"
61 )
62
63 is_spat_wall_time = LaunchConfiguration('is_spat_wall_time')
64 declare_is_spat_wall_time_arg = DeclareLaunchArgument(
65 name = 'is_spat_wall_time',
66 default_value = 'True',
67 description = "True if SPaT is being published based on wall clock"
68 )
69
70 subsystem_controller_default_param_file = os.path.join(
71 get_package_share_directory('subsystem_controllers'), 'config/guidance_controller_config.yaml')
72
73 mobilitypath_visualizer_param_file = os.path.join(
74 get_package_share_directory('mobilitypath_visualizer'), 'config/params.yaml')
75
76 trajectory_executor_param_file = os.path.join(
77 get_package_share_directory('trajectory_executor'), 'config/parameters.yaml')
78
79 route_param_file = os.path.join(
80 get_package_share_directory('route'), 'config/parameters.yaml')
81
82 trajectory_visualizer_param_file = os.path.join(
83 get_package_share_directory('trajectory_visualizer'), 'config/parameters.yaml')
84
85 guidance_param_file = os.path.join(
86 get_package_share_directory('guidance'), 'config/parameters.yaml')
87
88 arbitrator_param_file_path = os.path.join(
89 get_package_share_directory('arbitrator'), 'config/arbitrator_params.yaml')
90
91 plan_delegator_param_file = os.path.join(
92 get_package_share_directory('plan_delegator'), 'config/plan_delegator_params.yaml')
93
94 port_drayage_plugin_param_file = os.path.join(
95 get_package_share_directory('port_drayage_plugin'), 'config/parameters.yaml')
96
97 env_log_levels = EnvironmentVariable('CARMA_ROS_LOGGING_CONFIG', default_value='{ "default_level" : "WARN" }')
98
99 subsystem_controller_param_file = LaunchConfiguration('subsystem_controller_param_file')
100 declare_subsystem_controller_param_file_arg = DeclareLaunchArgument(
101 name = 'subsystem_controller_param_file',
102 default_value = subsystem_controller_default_param_file,
103 description = "Path to file containing override parameters for the subsystem controller"
104 )
105
106 # Below nodes are separated to individual container such that the nodes with reentrant services are within their separate container.
107 # When all nodes are within single container, it is prone to fail throwing runtime_error, and it is currently hypothesized to be
108 # because of this issue: https://github.com/ros2/rclcpp/issues/1212, where fix in the rclcpp library, so not able to be integrated at this moment:
109 # https://github.com/ros2/rclcpp/pull/1241. This issue was first discovered in this carma issue: https://github.com/usdot-fhwa-stol/carma-platform/issues/1961
110
111 # Nodes
112 carma_guidance_visualizer_container = ComposableNodeContainer(
113 package='carma_ros2_utils',
114 name='carma_guidance_visualizer_container',
115 executable='carma_component_container_mt',
116 namespace=GetCurrentNamespace(),
117 composable_node_descriptions=[
118 ComposableNode(
119 package='mobilitypath_visualizer',
120 plugin='mobilitypath_visualizer::MobilityPathVisualizer',
121 name='mobilitypath_visualizer_node',
122 extra_arguments=[
123 {'use_intra_process_comms': True},
124 {'--log-level' : GetLogLevel('mobilitypath_visualizer', env_log_levels) }
125 ],
126 remappings = [
127 ("mobility_path_msg", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_mobility_path" ] ),
128 ("incoming_mobility_path", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_mobility_path" ] ),
129 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference"])
130 ],
131 parameters=[
132 vehicle_characteristics_param_file,
133 mobilitypath_visualizer_param_file,
134 vehicle_config_param_file
135 ]
136 ),
137 ComposableNode(
138 package='trajectory_visualizer',
139 plugin='trajectory_visualizer::TrajectoryVisualizer',
140 name='trajectory_visualizer_node',
141 extra_arguments=[
142 {'use_intra_process_comms': True},
143 {'--log-level' : GetLogLevel('trajectory_visualizer', env_log_levels) }
144 ],
145 parameters=[
146 trajectory_visualizer_param_file,
147 vehicle_config_param_file
148 ]
149 )
150 ]
151 )
152
153 carma_plan_delegator_container = ComposableNodeContainer(
154 package='carma_ros2_utils',
155 name='carma_plan_delegator_container',
156 executable='carma_component_container_mt',
157 namespace=GetCurrentNamespace(),
158 composable_node_descriptions=[
159 ComposableNode(
160 package='plan_delegator',
161 plugin='plan_delegator::PlanDelegator',
162 name='plan_delegator',
163 extra_arguments=[
164 {'use_intra_process_comms': True},
165 {'--log-level' : GetLogLevel('plan_delegator', env_log_levels) }
166 ],
167 remappings = [
168 ("current_velocity", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle/twist" ] ),
169 ("current_pose", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] ),
170 ("vehicle_status", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle_status" ] ),
171 ("semantic_map", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/semantic_map" ] ),
172 ("map_update", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/map_update" ] ),
173 ("roadway_objects", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/roadway_objects" ] ),
174 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] ),
175 ("guidance_state", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/state" ] ),
176 ],
177 parameters=[
178 plan_delegator_param_file,
179 vehicle_config_param_file
180 ]
181 )
182 ]
183 )
184
185 carma_trajectory_executor_and_route_container = ComposableNodeContainer(
186 package='carma_ros2_utils',
187 name='carma_trajectory_executor_and_route_container',
188 executable='carma_component_container_mt',
189 namespace=GetCurrentNamespace(),
190 composable_node_descriptions=[
191 ComposableNode(
192 package='route',
193 plugin='route::Route',
194 name='route_node',
195 extra_arguments=[
196 {'use_intra_process_comms': True},
197 {'--log-level' : GetLogLevel('route', env_log_levels) }
198 ],
199 remappings = [
200 ("current_velocity", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle/twist" ] ),
201 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] ),
202 ("semantic_map", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/semantic_map" ] ),
203 ("map_update", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/map_update" ] ),
204 ("roadway_objects", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/roadway_objects" ] ),
205 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] )
206 ],
207 parameters=[
208 {'route_file_path': route_file_folder},
209 route_param_file,
210 vehicle_config_param_file
211 ]
212 ),
213 ComposableNode(
214 package='trajectory_executor',
215 plugin='trajectory_executor::TrajectoryExecutor',
216 name='trajectory_executor_node',
217 extra_arguments=[
218 {'use_intra_process_comms': True},
219 {'--log-level' : GetLogLevel('trajectory_executor', env_log_levels) }
220 ],
221 remappings = [
222 ("trajectory", "plan_trajectory"),
223 ],
224 parameters=[
225 trajectory_executor_param_file,
226 vehicle_config_param_file
227 ]
228 )
229 ]
230 )
231
232 carma_arbitrator_container = ComposableNodeContainer(
233 package='carma_ros2_utils',
234 name='carma_arbitrator_container',
235 executable='carma_component_container_mt',
236 namespace=GetCurrentNamespace(),
237 composable_node_descriptions=[
238 ComposableNode(
239 package='arbitrator',
240 plugin='arbitrator::ArbitratorNode',
241 name='arbitrator',
242 extra_arguments=[
243 {'use_intra_process_comms': True},
244 {'--log-level' : GetLogLevel('arbitrator', env_log_levels) }
245 ],
246 remappings = [
247 ("current_velocity", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle/twist" ] ),
248 ("guidance_state", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/state" ] ),
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 ],
254 parameters=[
255 arbitrator_param_file_path,
256 vehicle_config_param_file
257 ]
258 )
259 ]
260 )
261 carma_guidance_worker_container = ComposableNodeContainer(
262 package='carma_ros2_utils',
263 name='carma_guidance_worker_container',
264 executable='carma_component_container_mt',
265 namespace=GetCurrentNamespace(),
266 composable_node_descriptions=[
267 ComposableNode(
268 package='guidance',
269 plugin='guidance::GuidanceWorker',
270 name='guidance_node',
271 extra_arguments=[
272 {'use_intra_process_comms': True},
273 {'--log-level' : GetLogLevel('route', env_log_levels) }
274 ],
275 remappings = [
276 ("vehicle_status", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle_status" ] ),
277 ("robot_status", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/controller/robot_status" ] ),
278 ("enable_robotic", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/controller/enable_robotic" ] ),
279 ],
280 parameters=[
281 guidance_param_file,
282 vehicle_config_param_file
283 ]
284 )
285 ]
286 )
287
288 carma_port_drayage_plugin_container = ComposableNodeContainer(
289 package='carma_ros2_utils',
290 name='carma_port_drayage_plugin_container',
291 executable='carma_component_container_mt',
292 namespace=GetCurrentNamespace(),
293 composable_node_descriptions=[
294 ComposableNode(
295 package='port_drayage_plugin',
296 plugin='port_drayage_plugin::PortDrayagePlugin',
297 name='port_drayage_plugin_node',
298 extra_arguments=[
299 {'use_intra_process_comms': True},
300 {'--log-level' : GetLogLevel('port_drayage_plugin', env_log_levels) }
301 ],
302 remappings = [
303 ("guidance_state", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/state" ] ),
304 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] ),
305 ("current_pose", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] ),
306 ("incoming_mobility_operation", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_mobility_operation" ] ),
307 ("outgoing_mobility_operation", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_mobility_operation" ] ),
308 ("ui_instructions", [ EnvironmentVariable('CARMA_UI_NS', default_value=''), "/ui_instructions" ] )
309 ],
310 parameters=[
311 port_drayage_plugin_param_file,
312 vehicle_characteristics_param_file,
313 vehicle_config_param_file
314 ]
315 )
316 ]
317 )
318
319 twist_filter_container = ComposableNodeContainer(
320 package='carma_ros2_utils',
321 name='twist_filter_container',
322 executable='carma_component_container_mt',
323 namespace=GetCurrentNamespace(),
324 composable_node_descriptions=[
325 ComposableNode(
326 package='twist_filter',
327 plugin='twist_filter::TwistFilter',
328 name='twist_filter_node',
329 extra_arguments=[
330 {'use_intra_process_comms': True},
331 {'--log-level' : GetLogLevel('twist_filter', env_log_levels) }
332 ],
333 remappings = [
334 ("/accel_cmd", ["accel_cmd" ] ),
335 ("/brake_cmd", ["brake_cmd" ] ),
336 ("/gear_cmd", ["gear_cmd" ] ),
337 ("/mode_cmd", ["mode_cmd" ] ),
338 ("/remote_cmd", ["remote_cmd" ] ),
339 ("/steer_cmd", ["steer_cmd" ] ),
340 ("/emergency_stop", ["emergency_stop" ] ),
341 ("/state_cmd", ["state_cmd" ] )
342 ],
343 parameters=[
344 vehicle_config_param_file,
345 {'lowpass_gain_linear_x':0.1},
346 {'lowpass_gain_angular_z':0.0},
347 {'lowpass_gain_steering_angle':0.1}
348 ]
349 ),
350 ComposableNode(
351 package='twist_gate',
352 plugin='TwistGate',
353 name='twist_gate_node',
354 extra_arguments=[
355 {'use_intra_process_comms': True},
356 {'--log-level' : GetLogLevel('twist_gate', env_log_levels) }
357 ],
358 remappings = [
359 ("vehicle_cmd", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle_cmd" ] ),
360 ("/lamp_cmd", ["lamp_cmd" ] ),
361 ("/twist_cmd", ["twist_cmd" ] ),
362 ("/decision_maker/state", ["decision_maker/state" ] ),
363 ("/ctrl_cmd", ["ctrl_cmd" ] ),
364 ],
365 parameters = [
366 {'loop_rate':30.0},
367 {'use_decision_maker':False},
368 vehicle_config_param_file
369 ]
370 )
371 ]
372 )
373
374 # Launch plugins
375 plugins_group = GroupAction(
376 actions=[
377 PushRosNamespace("plugins"),
378 IncludeLaunchDescription(
379 PythonLaunchDescriptionSource([ThisLaunchFileDir(), '/plugins.launch.py']),
380 launch_arguments={
381 'route_file_folder' : route_file_folder,
382 'vehicle_calibration_dir' : vehicle_calibration_dir,
383 'vehicle_characteristics_param_file' : vehicle_characteristics_param_file,
384 'vehicle_config_param_file' : vehicle_config_param_file,
385 'enable_guidance_plugin_validator' : enable_guidance_plugin_validator,
386 'strategic_plugins_to_validate' : strategic_plugins_to_validate,
387 'tactical_plugins_to_validate' : tactical_plugins_to_validate,
388 'control_plugins_to_validate' : control_plugins_to_validate,
389 'subsystem_controller_param_file' : [vehicle_config_dir, '/SubsystemControllerParams.yaml'],
390 }.items()
391 ),
392 ]
393 )
394
395 # subsystem_controller which orchestrates the lifecycle of this subsystem's components
396 subsystem_controller = Node(
397 package='subsystem_controllers',
398 name='guidance_controller',
399 executable='guidance_controller',
400 parameters=[
401 subsystem_controller_default_param_file,
402 subsystem_controller_param_file,
403 {"use_sim_time" : use_sim_time},
404 {"is_spat_wall_time" : is_spat_wall_time}],
405 on_exit= Shutdown(), # Mark the subsystem controller as required
406 arguments=['--ros-args', '--log-level', GetLogLevel('subsystem_controllers', env_log_levels)]
407 )
408
409 return LaunchDescription([
410 declare_vehicle_config_param_file_arg,
411 declare_use_sim_time_arg,
412 declare_subsystem_controller_param_file_arg,
413 declare_is_spat_wall_time_arg,
414 carma_trajectory_executor_and_route_container,
415 carma_guidance_visualizer_container,
416 carma_guidance_worker_container,
417 carma_plan_delegator_container,
418 carma_arbitrator_container,
419 carma_port_drayage_plugin_container,
420 twist_filter_container,
421 plugins_group,
422 subsystem_controller
423 ])
def generate_launch_description()