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

Functions

def generate_launch_description ()
 

Function Documentation

◆ generate_launch_description()

def localization.generate_launch_description ( )
Launch Localization subsystem nodes

Definition at line 37 of file localization.launch.py.

38 """
39 Launch Localization subsystem nodes
40 """
41
42 env_log_levels = EnvironmentVariable('CARMA_ROS_LOGGING_CONFIG', default_value='{ "default_level" : "WARN" }')
43 vehicle_config_param_file = LaunchConfiguration('vehicle_config_param_file')
44 subsystem_controller_default_param_file = os.path.join(
45 get_package_share_directory('subsystem_controllers'), 'config/localization_controller_config.yaml')
46
47 subsystem_controller_param_file = LaunchConfiguration('subsystem_controller_param_file')
48 declare_subsystem_controller_param_file_arg = DeclareLaunchArgument(
49 name = 'subsystem_controller_param_file',
50 default_value = subsystem_controller_default_param_file,
51 description = "Path to file containing override parameters for the subsystem controller"
52 )
53
54 # Nodes
55 # TODO add ROS2 localization nodes here
56
57 gnss_to_map_convertor_param_file = os.path.join(
58 get_package_share_directory('gnss_to_map_convertor'), 'config/parameters.yaml')
59
60 localization_manager_convertor_param_file = os.path.join(
61 get_package_share_directory('localization_manager'), 'config/parameters.yaml')
62
63 vehicle_calibration_dir = LaunchConfiguration('vehicle_calibration_dir')
64 ndt_matching_param_file = [vehicle_calibration_dir, "/lidar_localizer/ndt_matching/params.yaml"]
65
66 # Declare launch arguments for points_map_loader
67 load_type = LaunchConfiguration('load_type')
68 declare_load_type= DeclareLaunchArgument(name = 'load_type', default_value = "noupdate")
69
70 single_pcd_path = LaunchConfiguration('single_pcd_path')
71 declare_single_pcd_path = DeclareLaunchArgument(name='single_pcd_path', default_value="['/opt/carma/maps/pcd_map.pcd']", description='Path to the map pcd file if using the noupdate load type')
72
73 area = LaunchConfiguration('area')
74 declare_area = DeclareLaunchArgument(name='area', default_value="1x1")
75
76 arealist_path = LaunchConfiguration('arealist_path')
77 declare_arealist_path = DeclareLaunchArgument(name='arealist_path', default_value="/opt/carma/maps/arealist.txt")
78
79 vector_map_file = LaunchConfiguration('vector_map_file')
80 declare_map_file = DeclareLaunchArgument(name='vector_map_file', default_value='vector_map.osm', description='Path to the map osm file if using the noupdate load type')
81
82 use_sim_time = LaunchConfiguration('use_sim_time')
83 declare_use_sim_time_arg = DeclareLaunchArgument(
84 name = 'use_sim_time',
85 default_value = 'False',
86 description = "True if simulation mode is on"
87 )
88
89 gnss_to_map_convertor_container = ComposableNodeContainer(
90 package='carma_ros2_utils',
91 name='gnss_to_map_convertor_container',
92 executable='carma_component_container_mt',
93 namespace=GetCurrentNamespace(),
94 composable_node_descriptions=[
95
96 ComposableNode(
97 package='gnss_to_map_convertor',
98 plugin='gnss_to_map_convertor::Node',
99 name='gnss_to_map_convertor',
100 extra_arguments=[
101 {'use_intra_process_comms': True},
102 {'--log-level' : GetLogLevel('gnss_to_map_convertor', env_log_levels) }
103 ],
104 remappings=[
105 ("gnss_fix_fused", [EnvironmentVariable('CARMA_INTR_NS', default_value=''),"/gnss_fix_fused"]),
106 ("georeference", "map_param_loader/georeference"),
107 ],
108 parameters=[ gnss_to_map_convertor_param_file, vehicle_config_param_file]
109 )
110 ])
111
112 localization_manager_container = ComposableNodeContainer(
113 package='carma_ros2_utils',
114 name='localization_manager_container',
115 executable='carma_component_container_mt',
116 namespace=GetCurrentNamespace(),
117 composable_node_descriptions=[
118 ComposableNode(
119 package='localization_manager',
120 plugin='localization_manager::Node',
121 name='localization_manager',
122 extra_arguments=[
123 {'use_intra_process_comms': True},
124 {'--log-level' : GetLogLevel('localization_manager', env_log_levels) }
125 ],
126 remappings=[
127
128 ],
129 parameters=[ localization_manager_convertor_param_file, vehicle_config_param_file ]
130 )
131 ])
132
133
134
135 # map param/tf loader
136 map_param_loader_container = ComposableNodeContainer(
137 package='carma_ros2_utils',
138 name='map_param_loader_container',
139 executable='carma_component_container_mt',
140 namespace=GetCurrentNamespace(),
141 composable_node_descriptions=[
142 ComposableNode(
143 package='map_file_ros2',
144 plugin='map_param_loader::MapParamLoader',
145 name='map_param_loader',
146 extra_arguments=[
147 {'use_intra_process_comms': True},
148 {'--log-level' : GetLogLevel('map_param_loader', env_log_levels) }
149 ],
150 remappings=[
151 ("georeference", "map_param_loader/georeference"),
152 ],
153 parameters=[ {'file_name' : vector_map_file }, vehicle_config_param_file]
154 )
155 ])
156
157 # Point Cloud map file loading process
158 pcd_map_file_loader_container = ComposableNodeContainer(
159 package='carma_ros2_utils',
160 name='map_file_nodes_container',
161 namespace=GetCurrentNamespace(),
162 executable='carma_component_container_mt',
163 composable_node_descriptions=[
164
165 ComposableNode(
166 package='map_file_ros2',
167 plugin='points_map_loader::PointsMapLoader',
168 name='points_map_loader',
169 extra_arguments=[
170 {'use_intra_process_comms': True},
171 {'--log-level' : GetLogLevel('points_map_loader', env_log_levels) }
172 ],
173 parameters=[
174 {'load_type' : load_type },
175 {'pcd_path_parameter' : single_pcd_path },
176 {'area' : area },
177 {'path_area_list' : arealist_path },
178 vehicle_config_param_file
179 ]
180 ),
181 ]
182 )
183
184 # Dead Reckoner
185 dead_reckoner_container = ComposableNodeContainer(
186 package='carma_ros2_utils',
187 name='dead_reckoner_container',
188 namespace=GetCurrentNamespace(),
189 executable='carma_component_container_mt',
190 composable_node_descriptions=[
191
192 ComposableNode(
193 package='dead_reckoner',
194 plugin='dead_reckoner::DeadReckoner',
195 name='dead_reckoner',
196 extra_arguments=[
197 {'use_intra_process_comms': True},
198 {'--log-level' : GetLogLevel('dead_reckoner', env_log_levels) }
199 ],
200 remappings=[
201 ("current_twist", [EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle/twist" ]),
202 ("current_odom", "vehicle/odom")
203 ],
204 parameters=[
205 vehicle_config_param_file
206 ]
207 ),
208 ]
209 )
210
211 # NDT Matching
212 # This namesapce sets the parameters which are not set by default in the ndt_matching.launch file
213 # These parameters are not in the ndt_matching node private namespace
214
215 ndt_matching_container = ComposableNodeContainer(
216 package='carma_ros2_utils',
217 name='ndt_matching_container',
218 namespace=GetCurrentNamespace(),
219 executable='carma_component_container_mt',
220 composable_node_descriptions=[
221
222 ComposableNode(
223 package='lidar_localizer_ros2',
224 plugin='ndt_matching::NDTMatching',
225 name='ndt_matching',
226 extra_arguments=[
227 {'use_intra_process_comms': True},
228 {'--log-level' : GetLogLevel('ndt_matching', env_log_levels) }
229 ],
230 remappings=[
231 ("/config/ndt", "config/ndt"),
232 ("/imu_raw", [ EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/imu_raw" ] ),
233 ('filtered_points', 'random_points'),
234 ('initialpose','managed_initialpose'),
235 ('/tf', '/tf_ndt_UNUSED'), #renaming /tf to avoid duplocation. Main /tf is published by ekf_localizer
236 ],
237 parameters=[
238 ndt_matching_param_file,
239 {'get_height' : True },
240 {'use_odom' : True },
241 {'use_gnss' : 0 },
242 {'gnss_reinit_fitness' : 10000.0 }, # Set to unreasonably high value to ensure no reinitialization occurs as it rarely works
243 {'base_frame': "base_link"}
244 ]
245 )
246 ]
247 )
248
249 # EKF Localizer
250 # Comment out to remove and change marked line in waypoint following.launch
251 ekf_localizer_container = ComposableNodeContainer(
252 condition=UnlessCondition(use_sim_time), # not needed in simulation
253 package='carma_ros2_utils',
254 name='ekf_localizer_container',
255 namespace=GetCurrentNamespace(),
256 executable='carma_component_container_mt',
257 composable_node_descriptions=[
258
259 ComposableNode(
260 package='ekf_localizer',
261 plugin='ekf_localizer::EKFLocalizer',
262 name='ekf_localizer',
263 extra_arguments=[
264 {'use_intra_process_comms': True},
265 {'--log-level' : GetLogLevel('ekf_localizer', env_log_levels) }
266 ],
267 remappings=[
268 ("in_pose","selected_pose"),
269 ("in_pose_with_covariance", "input_pose_with_cov_UNUSED"),
270 ("in_twist", [EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/vehicle/twist" ]),
271 ("in_twist_with_covariance", "input_twist_with_covariance_UNUSED"),
272 ("initialpose", "managed_initialpose"),
273 ("ekf_pose", "current_pose"),
274 ("ekf_pose_with_covariance", "current_pose_with_covariance"),
275 # remap to namespace/nodename/topic_name
276 ("debug", "~/debug"),
277 ("debug/measured_pose", "~/debug/measured_pose"),
278 ("estimated_yaw_bias", "~/estimated_yaw_bias")
279 ],
280 parameters=[
281 {'show_debug_info': False},
282 {'predict_frequency': 50.0},
283 {'enable_yaw_bias_estimation': True},
284 {'extend_state_step': 50},
285 {'pose_frame_id': 'map'},
286 {'child_frame_id': 'base_link'},
287 {'pose_additional_delay': 0.0},
288 {'pose_measure_uncertainty_time': 0.01},
289 {'pose_rate': 10.0},
290 {'pose_gate_dist': 10000.0},
291 {'pose_stddev_x': 0.05},
292 {'pose_stddev_y': 0.05},
293 {'pose_stddev_yaw': 0.025},
294 {'use_pose_with_covariance': False},
295 {'twist_additional_delay': 0.0},
296 {'twist_rate': 30.0},
297 {'twist_gate_dist': 10000.0},
298 {'twist_stddev_vx': 0.2},
299 {'twist_stddev_wz': 0.03},
300 {'proc_stddev_yaw_c': 0.005},
301 {'proc_stddev_yaw_bias_c': 0.001},
302 {'proc_stddev_vx_c': 0.1},
303 {'proc_stddev_wz_c': 0.05}
304 ],
305 )
306 ]
307 )
308
309
310
311 voxel_grid_filter_container = ComposableNodeContainer(
312 package='carma_ros2_utils',
313 name='voxel_grid_filter_container',
314 namespace=GetCurrentNamespace(),
315 executable='carma_component_container_mt',
316 composable_node_descriptions=[
317
318 # Launch the core node(s)
319 ComposableNode(
320 package='points_downsampler',
321 plugin='voxel_grid_filter::VoxelGridFilter',
322 name='voxel_grid_filter_node',
323 extra_arguments=[
324 {'use_intra_process_comms': True},
325 {'--log-level' : GetLogLevel('voxel_grid_filter', env_log_levels) }
326 ],
327 parameters=[
328 {"points_topic": [EnvironmentVariable('CARMA_INTR_NS', default_value=''), "/lidar/points_raw" ]},
329 {"output_log": False},
330 {"measurement_range": 200.0},
331 {"voxel_leaf_size": 3.0}
332 ],
333 ),
334 ]
335 )
336
337 random_filter_container = ComposableNodeContainer(
338 package='carma_ros2_utils',
339 name='random_filter_container',
340 namespace=GetCurrentNamespace(),
341 executable='carma_component_container_mt',
342 composable_node_descriptions=[
343
344 # Launch the core node(s)
345 ComposableNode(
346 package='points_downsampler',
347 plugin='random_filter::RandomFilter',
348 name='random_filter_node',
349 extra_arguments=[
350 {'use_intra_process_comms': True},
351 {'--log-level' : GetLogLevel('random_filter', env_log_levels) }
352 ],
353 parameters=[
354 {"points_topic": "filtered_points"},
355 {"output_log": False},
356 {"measurement_range": 200.0},
357 {"sample_num": 700}
358 ],
359 ),
360 ]
361 )
362
363
364 # subsystem_controller which orchestrates the lifecycle of this subsystem's components
365 subsystem_controller = Node(
366 package='subsystem_controllers',
367 name='localization_controller',
368 executable='localization_controller',
369 parameters=[
370 subsystem_controller_default_param_file,
371 subsystem_controller_param_file,
372 {"use_sim_time" : use_sim_time}], # Default file is loaded first followed by config file
373 on_exit= Shutdown(), # Mark the subsystem controller as required
374 arguments=['--ros-args', '--log-level', GetLogLevel('subsystem_controllers', env_log_levels)]
375 )
376
377 return LaunchDescription([
378 declare_subsystem_controller_param_file_arg,
379 declare_load_type,
380 declare_single_pcd_path,
381 declare_area,
382 declare_arealist_path,
383 declare_map_file,
384 declare_use_sim_time_arg,
385 gnss_to_map_convertor_container,
386 localization_manager_container,
387 dead_reckoner_container,
388 voxel_grid_filter_container,
389 random_filter_container,
390 map_param_loader_container,
391 pcd_map_file_loader_container,
392 ndt_matching_container,
393 ekf_localizer_container,
394 subsystem_controller
395 ])
def generate_launch_description()