Carma-platform v4.10.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 Namespace Reference

Classes

struct  Config
 Stuct containing the algorithm configuration values for GuidanceWorker. More...
 
class  GuidanceStateMachine
 
class  GuidanceWorker
 Worker class for the Guidance node. More...
 

Functions

def generate_launch_description ()
 

Function Documentation

◆ generate_launch_description()

def guidance.generate_launch_description ( )

Definition at line 39 of file guidance.launch.py.

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_param_file = LaunchConfiguration('vehicle_config_param_file')
49 declare_vehicle_config_param_file_arg = DeclareLaunchArgument(
50 name = 'vehicle_config_param_file',
51 default_value = "/opt/carma/vehicle/config/VehicleConfigParams.yaml",
52 description = "Path to file contain vehicle configuration parameters"
53 )
54 vehicle_config_dir = LaunchConfiguration('vehicle_config_dir')
55 declare_vehicle_config_dir_arg = DeclareLaunchArgument(
56 name = 'vehicle_config_dir',
57 default_value = "/opt/carma/vehicle/config",
58 description = "Path to vehicle configuration directory populated by carma-config"
59 )
60
61 use_sim_time = LaunchConfiguration('use_sim_time')
62 declare_use_sim_time_arg = DeclareLaunchArgument(
63 name = 'use_sim_time',
64 default_value = "False",
65 description = "True if simulation mode is on"
66 )
67
68 use_real_time_spat_in_sim = LaunchConfiguration('use_real_time_spat_in_sim')
69 declare_use_real_time_spat_in_sim_arg = DeclareLaunchArgument(
70 name = 'use_real_time_spat_in_sim',
71 default_value = 'False',
72 description = "True if SPaT is being published based on wall clock"
73 )
74
75 subsystem_controller_default_param_file = os.path.join(
76 get_package_share_directory('subsystem_controllers'), 'config/guidance_controller_config.yaml')
77
78 # Declare the global_params_override_file launch argument
79 # Parameters in this file will override any parameters loaded in their respective packages
80 global_params_override_file = LaunchConfiguration('global_params_override_file')
81 declare_global_params_override_file_arg = DeclareLaunchArgument(
82 name = 'global_params_override_file',
83 default_value = [vehicle_config_dir, "/GlobalParamsOverride.yaml"],
84 description = "Path to global file containing the parameters overwrite"
85 )
86
87 mobilitypath_visualizer_param_file = os.path.join(
88 get_package_share_directory('mobilitypath_visualizer'), 'config/params.yaml')
89
90 trajectory_executor_param_file = os.path.join(
91 get_package_share_directory('trajectory_executor'), 'config/parameters.yaml')
92
93 route_param_file = os.path.join(
94 get_package_share_directory('route'), 'config/parameters.yaml')
95
96 trajectory_visualizer_param_file = os.path.join(
97 get_package_share_directory('trajectory_visualizer'), 'config/parameters.yaml')
98
99 guidance_param_file = os.path.join(
100 get_package_share_directory('guidance'), 'config/parameters.yaml')
101
102 arbitrator_param_file_path = os.path.join(
103 get_package_share_directory('arbitrator'), 'config/arbitrator_params.yaml')
104
105 plan_delegator_param_file = os.path.join(
106 get_package_share_directory('plan_delegator'), 'config/plan_delegator_params.yaml')
107
108 port_drayage_plugin_param_file = os.path.join(
109 get_package_share_directory('port_drayage_plugin'), 'config/parameters.yaml')
110
111 env_log_levels = EnvironmentVariable('CARMA_ROS_LOGGING_CONFIG', default_value='{ "default_level" : "WARN" }')
112
113 subsystem_controller_param_file = LaunchConfiguration('subsystem_controller_param_file')
114 declare_subsystem_controller_param_file_arg = DeclareLaunchArgument(
115 name = 'subsystem_controller_param_file',
116 default_value = subsystem_controller_default_param_file,
117 description = "Path to file containing override parameters for the subsystem controller"
118 )
119
120 # Below nodes are separated to individual container such that the nodes with reentrant services are within their separate container.
121 # When all nodes are within single container, it is prone to fail throwing runtime_error, and it is currently hypothesized to be
122 # 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:
123 # 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
124
125 # Nodes
126 carma_guidance_visualizer_container = ComposableNodeContainer(
127 package='carma_ros2_utils',
128 name='carma_guidance_visualizer_container',
129 executable='carma_component_container_mt',
130 namespace=GetCurrentNamespace(),
131 composable_node_descriptions=[
132 ComposableNode(
133 package='mobilitypath_visualizer',
134 plugin='mobilitypath_visualizer::MobilityPathVisualizer',
135 name='mobilitypath_visualizer_node',
136 extra_arguments=[
137 {'use_intra_process_comms': True},
138 {'--log-level' : GetLogLevel('mobilitypath_visualizer', env_log_levels) }
139 ],
140 remappings = [
141 ("mobility_path_msg", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_mobility_path" ] ),
142 ("incoming_mobility_path", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_mobility_path" ] ),
143 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference"])
144 ],
145 parameters=[
146 vehicle_characteristics_param_file,
147 mobilitypath_visualizer_param_file,
148 vehicle_config_param_file,
149 global_params_override_file
150 ]
151 ),
152 ComposableNode(
153 package='trajectory_visualizer',
154 plugin='trajectory_visualizer::TrajectoryVisualizer',
155 name='trajectory_visualizer_node',
156 extra_arguments=[
157 {'use_intra_process_comms': True},
158 {'--log-level' : GetLogLevel('trajectory_visualizer', env_log_levels) }
159 ],
160 parameters=[
161 trajectory_visualizer_param_file,
162 vehicle_config_param_file,
163 global_params_override_file
164 ]
165 )
166 ]
167 )
168
169 carma_plan_delegator_container = ComposableNodeContainer(
170 package='carma_ros2_utils',
171 name='carma_plan_delegator_container',
172 executable='carma_component_container_mt',
173 namespace=GetCurrentNamespace(),
174 composable_node_descriptions=[
175 ComposableNode(
176 package='plan_delegator',
177 plugin='plan_delegator::PlanDelegator',
178 name='plan_delegator',
179 extra_arguments=[
180 {'use_intra_process_comms': True},
181 {'--log-level' : GetLogLevel('plan_delegator', env_log_levels) }
182 ],
183 remappings = [
184 ("current_velocity", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle/twist" ] ),
185 ("current_pose", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] ),
186 ("vehicle_status", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle_status" ] ),
187 ("semantic_map", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/semantic_map" ] ),
188 ("map_update", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/map_update" ] ),
189 ("roadway_objects", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/roadway_objects" ] ),
190 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] ),
191 ("guidance_state", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/state" ] ),
192 ],
193 parameters=[
194 plan_delegator_param_file,
195 vehicle_config_param_file,
196 global_params_override_file
197 ]
198 )
199 ]
200 )
201
202 carma_trajectory_executor_and_route_container = ComposableNodeContainer(
203 package='carma_ros2_utils',
204 name='carma_trajectory_executor_and_route_container',
205 executable='carma_component_container_mt',
206 namespace=GetCurrentNamespace(),
207 composable_node_descriptions=[
208 ComposableNode(
209 package='route',
210 plugin='route::Route',
211 name='route_node',
212 extra_arguments=[
213 {'use_intra_process_comms': True},
214 {'--log-level' : GetLogLevel('route', env_log_levels) }
215 ],
216 remappings = [
217 ("current_velocity", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle/twist" ] ),
218 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] ),
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 ],
224 parameters=[
225 {'route_file_path': route_file_folder},
226 route_param_file,
227 vehicle_config_param_file,
228 global_params_override_file
229 ]
230 ),
231 ComposableNode(
232 package='trajectory_executor',
233 plugin='trajectory_executor::TrajectoryExecutor',
234 name='trajectory_executor_node',
235 extra_arguments=[
236 {'use_intra_process_comms': True},
237 {'--log-level' : GetLogLevel('trajectory_executor', env_log_levels) }
238 ],
239 remappings = [
240 ("trajectory", "plan_trajectory"),
241 ],
242 parameters=[
243 trajectory_executor_param_file,
244 vehicle_config_param_file,
245 global_params_override_file
246 ]
247 )
248 ]
249 )
250
251 carma_arbitrator_container = ComposableNodeContainer(
252 package='carma_ros2_utils',
253 name='carma_arbitrator_container',
254 executable='carma_component_container_mt',
255 namespace=GetCurrentNamespace(),
256 composable_node_descriptions=[
257 ComposableNode(
258 package='arbitrator',
259 plugin='arbitrator::ArbitratorNode',
260 name='arbitrator',
261 extra_arguments=[
262 {'use_intra_process_comms': True},
263 {'--log-level' : GetLogLevel('arbitrator', env_log_levels) }
264 ],
265 remappings = [
266 ("current_velocity", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle/twist" ] ),
267 ("guidance_state", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/state" ] ),
268 ("semantic_map", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/semantic_map" ] ),
269 ("map_update", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/map_update" ] ),
270 ("roadway_objects", [ EnvironmentVariable('CARMA_ENV_NS', default_value=''), "/roadway_objects" ] ),
271 ("incoming_spat", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_spat" ] )
272 ],
273 parameters=[
274 arbitrator_param_file_path,
275 vehicle_config_param_file,
276 global_params_override_file
277 ]
278 )
279 ]
280 )
281 carma_guidance_worker_container = ComposableNodeContainer(
282 package='carma_ros2_utils',
283 name='carma_guidance_worker_container',
284 executable='carma_component_container_mt',
285 namespace=GetCurrentNamespace(),
286 composable_node_descriptions=[
287 ComposableNode(
288 package='guidance',
289 plugin='guidance::GuidanceWorker',
290 name='guidance_node',
291 extra_arguments=[
292 {'use_intra_process_comms': True},
293 {'--log-level' : GetLogLevel('route', env_log_levels) }
294 ],
295 remappings = [
296 ("vehicle_status", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle_status" ] ),
297 ("robot_status", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/controller/robot_status" ] ),
298 ("enable_robotic", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/controller/enable_robotic" ] ),
299 ],
300 parameters=[
301 guidance_param_file,
302 vehicle_config_param_file,
303 global_params_override_file
304 ]
305 )
306 ]
307 )
308
309 carma_port_drayage_plugin_container = ComposableNodeContainer(
310 package='carma_ros2_utils',
311 name='carma_port_drayage_plugin_container',
312 executable='carma_component_container_mt',
313 namespace=GetCurrentNamespace(),
314 composable_node_descriptions=[
315 ComposableNode(
316 package='port_drayage_plugin',
317 plugin='port_drayage_plugin::PortDrayagePlugin',
318 name='port_drayage_plugin_node',
319 extra_arguments=[
320 {'use_intra_process_comms': True},
321 {'--log-level' : GetLogLevel('port_drayage_plugin', env_log_levels) }
322 ],
323 remappings = [
324 ("guidance_state", [ EnvironmentVariable('CARMA_GUIDE_NS', default_value=''), "/state" ] ),
325 ("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] ),
326 ("current_pose", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] ),
327 ("incoming_mobility_operation", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_mobility_operation" ] ),
328 ("outgoing_mobility_operation", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_mobility_operation" ] ),
329 ("ui_instructions", [ EnvironmentVariable('CARMA_UI_NS', default_value=''), "/ui_instructions" ] )
330 ],
331 parameters=[
332 port_drayage_plugin_param_file,
333 vehicle_characteristics_param_file,
334 vehicle_config_param_file,
335 global_params_override_file
336 ]
337 )
338 ]
339 )
340
341 twist_filter_container = ComposableNodeContainer(
342 package='carma_ros2_utils',
343 name='twist_filter_container',
344 executable='carma_component_container_mt',
345 namespace=GetCurrentNamespace(),
346 composable_node_descriptions=[
347 ComposableNode(
348 package='twist_filter',
349 plugin='twist_filter::TwistFilter',
350 name='twist_filter_node',
351 extra_arguments=[
352 {'use_intra_process_comms': True},
353 {'--log-level' : GetLogLevel('twist_filter', env_log_levels) }
354 ],
355 remappings = [
356 ("/accel_cmd", ["accel_cmd" ] ),
357 ("/brake_cmd", ["brake_cmd" ] ),
358 ("/gear_cmd", ["gear_cmd" ] ),
359 ("/mode_cmd", ["mode_cmd" ] ),
360 ("/remote_cmd", ["remote_cmd" ] ),
361 ("/steer_cmd", ["steer_cmd" ] ),
362 ("/emergency_stop", ["emergency_stop" ] ),
363 ("/state_cmd", ["state_cmd" ] )
364 ],
365 parameters=[
366 vehicle_config_param_file,
367 {'lowpass_gain_linear_x':0.1},
368 {'lowpass_gain_angular_z':0.0},
369 {'lowpass_gain_steering_angle':0.1},
370 global_params_override_file
371 ]
372 ),
373 ComposableNode(
374 package='twist_gate',
375 plugin='TwistGate',
376 name='twist_gate_node',
377 extra_arguments=[
378 {'use_intra_process_comms': True},
379 {'--log-level' : GetLogLevel('twist_gate', env_log_levels) }
380 ],
381 remappings = [
382 ("vehicle_cmd", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle_cmd" ] ),
383 ("/lamp_cmd", ["lamp_cmd" ] ),
384 ("/twist_cmd", ["twist_cmd" ] ),
385 ("/decision_maker/state", ["decision_maker/state" ] ),
386 ("/ctrl_cmd", ["ctrl_cmd" ] ),
387 ],
388 parameters = [
389 {'loop_rate':30.0},
390 {'use_decision_maker':False},
391 vehicle_config_param_file,
392 global_params_override_file
393 ]
394 )
395 ]
396 )
397
398 # Launch plugins
399 plugins_group = GroupAction(
400 actions=[
401 PushRosNamespace("plugins"),
402 IncludeLaunchDescription(
403 PythonLaunchDescriptionSource([ThisLaunchFileDir(), '/plugins.launch.py']),
404 launch_arguments={
405 'route_file_folder' : route_file_folder,
406 'global_params_override_file' : global_params_override_file,
407 'vehicle_calibration_dir' : vehicle_calibration_dir,
408 'vehicle_characteristics_param_file' : vehicle_characteristics_param_file,
409 'vehicle_config_param_file' : vehicle_config_param_file,
410 'enable_guidance_plugin_validator' : enable_guidance_plugin_validator,
411 'strategic_plugins_to_validate' : strategic_plugins_to_validate,
412 'tactical_plugins_to_validate' : tactical_plugins_to_validate,
413 'control_plugins_to_validate' : control_plugins_to_validate,
414 'subsystem_controller_param_file' : [vehicle_config_dir, '/SubsystemControllerParams.yaml'],
415 }.items()
416 ),
417 ]
418 )
419
420 # subsystem_controller which orchestrates the lifecycle of this subsystem's components
421 subsystem_controller = Node(
422 package='subsystem_controllers',
423 name='guidance_controller',
424 executable='guidance_controller',
425 parameters=[
426 subsystem_controller_default_param_file,
427 subsystem_controller_param_file,
428 {"use_sim_time" : use_sim_time},
429 {"use_real_time_spat_in_sim" : use_real_time_spat_in_sim}],
430 on_exit= Shutdown(), # Mark the subsystem controller as required
431 arguments=['--ros-args', '--log-level', GetLogLevel('subsystem_controllers', env_log_levels)]
432 )
433
434 return LaunchDescription([
435 declare_vehicle_config_param_file_arg,
436 declare_vehicle_config_dir_arg,
437 declare_global_params_override_file_arg,
438 declare_use_sim_time_arg,
439 declare_subsystem_controller_param_file_arg,
440 declare_use_real_time_spat_in_sim_arg,
441 carma_trajectory_executor_and_route_container,
442 carma_guidance_visualizer_container,
443 carma_guidance_worker_container,
444 carma_plan_delegator_container,
445 carma_arbitrator_container,
446 carma_port_drayage_plugin_container,
447 twist_filter_container,
448 plugins_group,
449 subsystem_controller
450 ])
def generate_launch_description()