forked from carlosmccosta/dynamic_robot_localization_tests
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathlocalization_tests.launch
529 lines (457 loc) · 39.1 KB
/
localization_tests.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<!-- ####################################################### arguments #################################################### -->
<env name="GAZEBO_MODEL_PATH" value='$(find crob_gazebo_models)/models:$(optenv GAZEBO_MODEL_PATH "")' />
<arg name="show_rviz" default="1" />
<arg name="show_plots" default="1" />
<!-- ==================================== localization systems -->
<arg name="use_dynamic_robot_localization" default="1" />
<arg name="use_odometry_as_localization_system" default="1" />
<arg name="use_static_odometry_tf" default="0" />
<arg name="use_ethzasl_icp_mapper" default="0" />
<arg name="use_amcl" default="0" />
<arg name="use_amcl_simulated" default="0" />
<arg name="use_ekf" default="0" />
<arg name="use_gmapping" default="0" />
<arg name="use_hector" default="0" />
<arg name="use_crsm" default="0" />
<arg name="use_no_localization_system" default="0" />
<arg name="ethzasl_icp_mapper_min_registration_overlap" default="0.47" />
<arg name="ethzasl_icp_mapper_icp_config_filename" default="icp.yaml" />
<!-- ==================================== rosbags -->
<arg name="record_rosbags" default="0" />
<arg name="record_rosbags_topics" default="/guardian/base_pose_ground_truth /guardian/laser_horizontal_back /guardian/laser_tilt_front /guardian/cmd_vel /guardian/odom /guardian/imu_data /tf /tf_static /rosout" />
<arg name="compress_rosbags" default="1" />
<arg name="record_localization_results" default="0" />
<arg name="record_localization_results_paths" default="0" />
<arg name="record_localization_system_resources_usage" default="0" />
<arg name="record_parameters" default="0" />
<arg name="record_rosbags_options" default="--bz2" if="$(arg compress_rosbags)"/>
<arg name="record_rosbags_options" default="" unless="$(arg compress_rosbags)"/>
<arg name="record_localization_results_topics" default="/dynamic_robot_localization/diagnostics /dynamic_robot_localization/localization_detailed /dynamic_robot_localization/localization_pose /dynamic_robot_localization/localization_error /dynamic_robot_localization/odometry_error /dynamic_robot_localization/localization_times /dynamic_robot_localization/reference_keypoints /dynamic_robot_localization/ambient_keypoints /dynamic_robot_localization/localization_initial_pose_estimations /dynamic_robot_localization/aligned_pointcloud_inliers /dynamic_robot_localization/aligned_pointcloud_outliers /dynamic_robot_localization/ambient_pointcloud_filtered /guardian/base_pose_ground_truth /pose_ground_truth /tf /tf_static /rosout /amcl_pose /particlecloud" if="$(arg use_dynamic_robot_localization)"/>
<arg name="record_localization_results_topics" default="/amcl/localization_error /amcl/odometry_error /guardian/base_pose_ground_truth /pose_ground_truth /tf /tf_static /rosout /amcl_pose /particlecloud" if="$(arg use_amcl)"/>
<arg name="record_localization_results_topics" default="/ethzasl_icp_mapper/groundtruth_poses /ethzasl_icp_mapper/localization_error /ethzasl_icp_mapper/localization_poses /icp_pose /trajectory /trajectory_gt /trajectory_drl /trajectory_odom /rosout /tf" if="$(arg use_ethzasl_icp_mapper)" />
<arg name="record_localization_results_topics" default="" if="$(arg use_no_localization_system)" />
<!-- <arg name="record_localization_results_topics" default="-a" /> -->
<arg name="use_gazebo" default="0" />
<arg name="play_rosbags" default="1" />
<arg name="play_rosbags_rate" default="1.0" />
<arg name="play_rosbags_options" default="" />
<!-- ==================================== robot configurations -->
<arg name="guardian_use_schunk_arm" default="false" />
<arg name="guardian_use_wheels" default="true" />
<arg name="guardian_use_planar_lasers" default="true" />
<!-- <arg name="odometry_topic" default="" /> -->
<arg name="twist_topic" default="" />
<arg name="imu_topic" default="" />
<arg name="odometry_topic" default="/guardian/odom" />
<!-- <arg name="twist_topic" default="/guardian/cmd_vel" /> -->
<!-- <arg name="imu_topic" default="/guardian/imu_data" /> -->
<!-- ==================================== environment configurations -->
<arg name="use_6_dof" default="0" />
<arg name="use_fast_path" default="0" />
<arg name="use_tof" default="0" />
<arg name="world_name" default="ship_interior" />
<arg name="world_rosbag_suffix" default="" unless="$(arg use_6_dof)" />
<arg name="world_rosbag_suffix" default="_with_tilting_laser" if="$(arg use_6_dof)" />
<arg name="world_rosbag_path_suffix" default="" unless="$(arg use_fast_path)" />
<arg name="world_rosbag_path_suffix" default="_fast" if="$(arg use_fast_path)" />
<arg name="world_rosbag_folder" default="$(find dynamic_robot_localization_tests)/datasets/ship_interior" />
<arg name="world_rosbag_filename" default="$(arg world_rosbag_folder)/$(arg world_name)$(arg world_rosbag_suffix)$(arg world_rosbag_path_suffix)" />
<arg name="world_rosbag_play_extra_filenames" default="" />
<arg name="world_rosbag_results_filename" default="$(arg world_rosbag_filename)_results" />
<!-- ==================================== localization system selection -->
<!-- dynamic localization system -->
<arg name="process_reference_cloud" default="0" />
<arg name="recompute_point_features" default="0" />
<arg name="load_point_features" default="0" />
<arg name="save_point_features" default="0" />
<arg name="configuration_files_suffix" default="_2d" unless="$(arg use_6_dof)" />
<arg name="configuration_files_suffix" default="_3d" if="$(arg use_6_dof)" />
<arg name="configuration_files_tof_suffix" default="" unless="$(arg use_tof)" />
<arg name="configuration_files_tof_suffix" default="_tof" if="$(arg use_tof)" />
<arg name="yaml_configuration_base_filename" default="$(find dynamic_robot_localization)/yaml/configs/pose_tracking/static" />
<arg name="yaml_configuration_filters_filename" default="$(find dynamic_robot_localization)/yaml/configs/filters/filters$(arg configuration_files_suffix)$(arg configuration_files_tof_suffix).yaml" />
<arg name="yaml_configuration_pose_estimation_filename" default="$(find dynamic_robot_localization)/yaml/configs/pose_estimation/initial_pose_estimation$(arg configuration_files_suffix).yaml" />
<arg name="yaml_configuration_tracking_filename" default="$(arg yaml_configuration_base_filename)$(arg world_rosbag_path_suffix)$(arg configuration_files_suffix)$(arg configuration_files_tof_suffix).yaml" />
<arg name="yaml_configuration_recovery_filename" default="$(find dynamic_robot_localization)/yaml/configs/pose_recovery/recovery$(arg configuration_files_suffix).yaml" />
<arg name="reference_pointcloud_type_3d" default="false" unless="$(arg use_6_dof)" />
<arg name="reference_pointcloud_type_3d" default="true" if="$(arg use_6_dof)" />
<arg name="reference_pointcloud_update_mode" default="NoIntegration" /> <!-- NoIntegration | FullIntegration | InliersIntegration | OutliersIntegration -->
<arg name="reference_pointcloud_filename" default="$(find dynamic_robot_localization_tests)/maps/ship_interior/tridimensional/pcd/ship_interior_25mm_n30.pcd" if="$(arg process_reference_cloud)" />
<arg name="reference_pointcloud_filename" default="$(find dynamic_robot_localization_tests)/maps/ship_interior/tridimensional/cache/ship_interior_preprocessed_25mm.pcd" unless="$(arg process_reference_cloud)" />
<arg name="reference_pointcloud_preprocessed_save_filename" default="$(find dynamic_robot_localization_tests)/maps/ship_interior/tridimensional/cache/ship_interior_preprocessed_25mm.pcd" if="$(arg process_reference_cloud)" />
<arg name="reference_pointcloud_preprocessed_save_filename" default="" unless="$(arg process_reference_cloud)" />
<arg name="reference_pointcloud_keypoints_filename" default="" if="$(arg recompute_point_features)" />
<arg name="reference_pointcloud_keypoints_filename" default="$(find dynamic_robot_localization_tests)/maps/ship_interior/tridimensional/cache/ship_interior_sift_keypoints_25mm.pcd" unless="$(arg recompute_point_features)" />
<arg name="reference_pointcloud_keypoints_save_filename" default="" unless="$(arg recompute_point_features)" />
<arg name="reference_pointcloud_keypoints_save_filename" default="$(find dynamic_robot_localization_tests)/maps/ship_interior/tridimensional/cache/ship_interior_sift_keypoints_25mm.pcd" if="$(arg recompute_point_features)" />
<arg name="reference_pointcloud_descriptors_filename" default="" if="$(arg recompute_point_features)" />
<arg name="reference_pointcloud_descriptors_filename" default="$(find dynamic_robot_localization_tests)/maps/ship_interior/tridimensional/cache/ship_interior_fpfh_descriptors_25mm.pcd" unless="$(arg recompute_point_features)" />
<arg name="reference_pointcloud_descriptors_save_filename" default="" unless="$(arg recompute_point_features)" />
<arg name="reference_pointcloud_descriptors_save_filename" default="$(find dynamic_robot_localization_tests)/maps/ship_interior/tridimensional/cache/ship_interior_fpfh_descriptors_25mm.pcd" if="$(arg recompute_point_features)" />
<arg name="publish_last_pose_tf_timeout_seconds" default="-3.0" />
<!-- ==================================== localization system evaluation -->
<arg name="record_localization_system_process_name" default="drl_localization_node" if="$(arg use_dynamic_robot_localization)" />
<arg name="record_localization_system_process_name" default="ethzasl_icp_mapper" if="$(arg use_ethzasl_icp_mapper)" />
<arg name="record_localization_system_process_name" default="amcl" if="$(arg use_amcl)" />
<arg name="record_localization_system_process_name" default="" if="$(arg use_no_localization_system)" />
<arg name="compute_localization_error" default="1" />
<arg name="localization_error_msgs_namespace" default="dynamic_robot_localization" if="$(arg use_dynamic_robot_localization)" />
<arg name="localization_error_msgs_namespace" default="ethzasl_icp_mapper" if="$(arg use_ethzasl_icp_mapper)" />
<arg name="localization_error_msgs_namespace" default="amcl" if="$(arg use_amcl)" />
<arg name="localization_error_msgs_namespace" default="odom" if="$(arg use_no_localization_system)" />
<arg name="publish_tf_map_odom" default="1" />
<arg name="publish_pose_tf_rate" default="-10" />
<arg name="map_frame_id" default="map" />
<arg name="map_server_frame_id" default="$(arg map_frame_id)" />
<arg name="map_server_topic" default="map" />
<arg name="map_odom_only_frame_id" default="map_odom_only" />
<arg name="odom_frame_id" default="odom" />
<arg name="base_link_frame_id" default="base_footprint" />
<arg name="sensor_frame_id" default="$(arg base_link_frame_id)" unless="$(arg use_tof)" />
<arg name="sensor_frame_id" default="camera_depth_optical_frame" if="$(arg use_tof)" />
<arg name="invert_tf_transform" default="false" />
<arg name="invert_tf_hierarchy" default="false" />
<arg name="transform_pose_to_map_frame_id" default="true" />
<arg name="map_ground_truth_frame_id" default="map_ground_truth" />
<arg name="map_ground_truth_frame_id_source" default="$(arg base_link_frame_id)" />
<arg name="localization_ground_truth_frame_id" default="$(arg map_ground_truth_frame_id)" />
<arg name="publish_ground_truth" default="true" unless="$(arg play_rosbags)" />
<arg name="publish_ground_truth" default="false" if="$(arg play_rosbags)" />
<arg name="localization_system_pose_stamped_topic" default="localization_pose" if="$(arg use_dynamic_robot_localization)" />
<arg name="localization_system_pose_stamped_topic" default="/icp_pose" if="$(arg use_ethzasl_icp_mapper)" />
<arg name="localization_system_pose_stamped_topic" default="/amcl_pose" if="$(arg use_amcl)" />
<arg name="localization_system_pose_stamped_topic" default="" if="$(arg use_no_localization_system)" />
<arg name="ground_truth_pose_stamped_topic" default="" />
<arg name="ground_truth_pose_with_covariance_stamped_topic" default="" />
<arg name="ground_truth_odometry_topic" default="/guardian/base_pose_ground_truth" />
<arg name="ground_truth_filename" default="" />
<arg name="ground_truth_tf_time_offset" default="0.0" />
<!-- ==================================== rviz configs -->
<arg name="rviz_folder" default="$(find dynamic_robot_localization_tests)/rviz/guardian/ship_interior" />
<arg name="rviz_config" default="-d $(arg rviz_folder)/dynamic_robot_localization_planar.rviz" unless="$(arg use_6_dof)" />
<arg name="rviz_config" default="-d $(arg rviz_folder)/dynamic_robot_localization_tridimensional.rviz" if="$(arg use_6_dof)" />
<!-- ==================================== 3d maps -->
<arg name="reference_pointcloud_available" default="1" />
<arg name="use_octomap_for_dynamic_map_update" default="0" />
<arg name="use_octomap_only_to_build_occupancy_grid" default="0" />
<arg name="octomap_pointcloud_topic" default="aligned_pointcloud" /> <!-- ambient_pointcloud | aligned_pointcloud | aligned_pointcloud_outliers | aligned_pointcloud_inliers -->
<arg name="octomap_file" default="" />
<arg name="octomap_resolution" default="0.01" />
<arg name="octomap_minimum_amount_of_time_between_ros_msg_publishing" default="5.0" />
<arg name="octomap_minimum_number_of_integrations_before_ros_msg_publishing" default="10" />
<arg name="octomap_override_sensor_z" default="true" />
<arg name="octomap_override_sensor_z_value" default="0.0" />
<!-- <arg name="map_file" default="$(find dynamic_robot_localization_tests)/maps/ship_interior/tridimensional/octomap/ship_interior_10mm.bt" /> -->
<!-- <arg name="octomap_file" default="$(find dynamic_robot_localization_tests)/maps/ship_interior/tridimensional/octomap/ship_interior_10mm_dynamic.ot" /> -->
<!-- ==================================== 2d maps -->
<arg name="use_map_server" default="1" />
<arg name="map_file" default="$(find dynamic_robot_localization_tests)/maps/ship_interior/planar/ship_interior.yaml" unless="$(arg use_octomap_for_dynamic_map_update)" />
<!-- <arg name="map_file" default="$(find dynamic_robot_localization_tests)/maps/ship_interior/planar/ship_interior_10mm.yaml" unless="$(arg use_octomap_for_dynamic_map_update)" /> -->
<arg name="map_file" default="$(find dynamic_robot_localization_tests)/maps/ship_interior/planar/ship_interior_dynamic_10cm_height.yaml" if="$(arg use_octomap_for_dynamic_map_update)" />
<arg name="initial_2d_map_file" default="$(arg map_file)" />
<!-- ==================================== robot initial pose -->
<arg name="robot_initial_pose_in_base_to_map" default="true" />
<arg name="robot_initial_pose_available" default="true" />
<arg name="robot_initial_x" default="0.0" />
<arg name="robot_initial_y" default="0.0" />
<arg name="robot_initial_z" default="0.0" />
<arg name="robot_initial_roll" default="0.0" />
<arg name="robot_initial_pitch" default="0.0" />
<arg name="robot_initial_yaw" default="0.0" />
<!-- ==================================== robot sensor configuration -->
<arg name="use_simulated_kinect" default="false" />
<arg name="use_tilt_on_front_laser" default="0" unless="$(arg use_6_dof)" />
<arg name="use_tilt_on_front_laser" default="1" if="$(arg use_6_dof)" />
<arg name="use_laser_assembler" default="1" unless="$(arg use_tof)" />
<arg name="use_laser_assembler" default="0" if="$(arg use_tof)" />
<arg name="assemble_lasers_on_map_frame" default="0" /> <!-- if false -> assembles lasers on odom frame -->
<arg name="laser_assembly_frame" default="$(arg map_frame_id)" if="$(arg assemble_lasers_on_map_frame)" />
<arg name="laser_assembly_frame" default="$(arg odom_frame_id)" unless="$(arg assemble_lasers_on_map_frame)" />
<arg name="number_of_tf_queries_for_spherical_interpolation" default="4" />
<arg name="min_range_cutoff_percentage_offset" default="2.00" />
<arg name="max_range_cutoff_percentage_offset" default="0.95" />
<arg name="laser_scan_topics" default="/guardian/laser_tilt_front+/guardian/laser_horizontal_back" />
<arg name="laser_scan_topic_amcl" default="/guardian/laser_tilt_front" />
<arg name="ambient_pointcloud_topic" default="ambient_pointcloud" unless="$(arg use_tof)" />
<arg name="ambient_pointcloud_topic" default="/camera/depth/points" if="$(arg use_tof)" />
<arg name="reference_costmap_topic" default="/map" />
<arg name="reference_pointcloud_topic" default="" />
<arg name="relay_back_laser_to_front_laser" default="1" if="$(arg use_amcl)" />
<arg name="relay_back_laser_to_front_laser" default="0" unless="$(arg use_amcl)" />
<arg name="number_of_scans_to_assemble_per_cloud" default="2" unless="$(arg use_6_dof)" />
<arg name="number_of_scans_to_assemble_per_cloud" default="4" if="$(arg use_6_dof)" />
<arg name="min_number_of_scans_to_assemble_per_cloud" default="2" />
<arg name="max_number_of_scans_to_assemble_per_cloud" default="4" />
<arg name="min_timeout_seconds_for_cloud_assembly" default="0.15" />
<arg name="max_timeout_seconds_for_cloud_assembly" default="1.1" />
<arg name="max_linear_velocity" default="0.025" />
<arg name="max_angular_velocity" default="0.174532925" />
<arg name="timeout_for_cloud_assembly" default="1.0" />
<!-- ==================================== movement paths -->
<arg name="move_robot_on_path" default="0" />
<arg name="robot_path" default="$(find dynamic_robot_localization_tests)/maps/ship_interior/path" />
<!-- <arg name="system_command_after_path_finished" default="" /> -->
<!-- <arg name="system_command_after_path_finished" default="killall -SIGINT rlt_robot_localization_error_node AND killall -SIGINT drl_localization_node" /> -->
<arg name="system_command_after_path_finished" if="$(arg record_rosbags)" default="sleep 2 AND killall -SIGINT record" />
<arg name="system_command_after_path_finished" unless="$(arg record_rosbags)" default="" />
<!-- <arg name="system_command_after_path_finished" unless="$(arg record_rosbags)"
default="
rosrun dynamic_reconfigure dynparam set /dynamic_robot_localization/laserscan_to_pointcloud_assembler number_of_scans_to_assemble_per_cloud 25 AND
rosrun dynamic_reconfigure dynparam set /dynamic_robot_localization/laserscan_to_pointcloud_assembler timeout_for_cloud_assembly 2.5 AND
rosrun dynamic_reconfigure dynparam set /dynamic_robot_localization/laserscan_to_pointcloud_assembler laser_scan_topic $(arg laser_scan_topics) AND
sleep 10 AND
killall -SIGINT rlt_robot_localization_error_node AND
killall -SIGINT drl_localization_node" /> -->
<!-- #################################################### gazebo simulator ################################################ -->
<param name="/use_sim_time" type="bool" value="true" if="$(arg play_rosbags)" />
<param name="/use_sim_time" type="bool" value="false" unless="$(arg play_rosbags)" />
<include file="$(find guardian_gazebo)/launch/guardian.launch" if="$(arg use_gazebo)" >
<arg name="world_model" default="$(find dynamic_robot_localization_tests)/worlds/$(arg world_name).world" />
<arg name="rviz_config" default="$(arg rviz_config)" />
<arg name="use_tilt_on_front_laser" default="$(arg use_tilt_on_front_laser)" />
<arg name="use_simulated_kinect" default="$(arg use_simulated_kinect)" />
<arg name="robot_initial_x" default="$(arg robot_initial_x)" />
<arg name="robot_initial_y" default="$(arg robot_initial_y)" />
<arg name="robot_initial_z" default="$(arg robot_initial_z)" />
<arg name="robot_initial_yaw" default="$(arg robot_initial_yaw)" />
<arg name="use_schunk_arm" default="$(arg guardian_use_schunk_arm)" />
<arg name="use_wheels" default="$(arg guardian_use_wheels)" />
<arg name="use_planar_lasers" default="$(arg guardian_use_planar_lasers)" />
</include>
<node pkg="tf" type="static_transform_publisher" name="odom_tf" args="0 0 0 0 0 0 odom base_footprint 5" if="$(arg use_static_odometry_tf)" />
<!-- #################################################### ground truth ################################################ -->
<!-- <node pkg="pose_to_tf_publisher" type="pose_to_tf_publisher_node" name="pose_to_tf_publisher_node_ground_truth" ns="dynamic_robot_localization" output="screen" if="$(arg publish_ground_truth)" launch-prefix="gdbserver localhost:1339" > -->
<node pkg="pose_to_tf_publisher" type="pose_to_tf_publisher_node" name="pose_to_tf_publisher_node_ground_truth" ns="dynamic_robot_localization" output="screen" if="$(arg publish_ground_truth)" >
<param name="publish_rate" type="double" value="-1.0" />
<param name="pose_stamped_topic" type="str" value="$(arg ground_truth_pose_stamped_topic)" />
<param name="pose_with_covariance_stamped_topic" type="str" value="$(arg ground_truth_pose_with_covariance_stamped_topic)" />
<param name="odometry_topic" type="str" value="$(arg ground_truth_odometry_topic)" />
<param name="poses_filename" type="str" value="$(arg ground_truth_filename)" />
<param name="map_frame_id" type="str" value="$(arg map_ground_truth_frame_id)" />
<param name="odom_frame_id" type="str" value="" /> <!-- publishes tf [ ground_truth -> base_link ] directly -->
<param name="base_link_frame_id" type="str" value="$(arg map_ground_truth_frame_id_source)" />
<param name="invert_tf_transform" type="bool" value="true" />
<param name="invert_tf_hierarchy" type="bool" value="true" />
<param name="tf_time_offset" type="double" value="$(arg ground_truth_tf_time_offset)" />
<param name="transform_pose_to_map_frame_id" type="bool" value="false" />
<param name="initial_x" type="double" value="$(arg robot_initial_x)" />
<param name="initial_y" type="double" value="$(arg robot_initial_y)" />
<param name="initial_z" type="double" value="$(arg robot_initial_z)" />
<param name="initial_roll" type="double" value="$(arg robot_initial_roll)" />
<param name="initial_pitch" type="double" value="$(arg robot_initial_pitch)" />
<param name="initial_yaw" type="double" value="$(arg robot_initial_yaw)" />
</node>
<include file="$(find robot_localization_tools)/launch/robot_localization_error.launch" ns="$(arg localization_error_msgs_namespace)" if="$(arg compute_localization_error)" >
<arg name="map_frame_id" default="$(arg map_frame_id)" />
<arg name="map_odom_only_frame_id" default="$(arg map_odom_only_frame_id)" />
<arg name="odom_frame_id" default="$(arg odom_frame_id)" />
<arg name="base_link_frame_id" default="$(arg base_link_frame_id)" />
<arg name="localization_ground_truth_frame_id" default="$(arg localization_ground_truth_frame_id)" />
<arg name="use_degrees_in_angles" default="true" />
<arg name="use_millimeters_in_distances" default="true" />
<arg name="use_6_dof" default="$(arg use_6_dof)" />
<arg name="publish_rate" default="-1.0" />
<arg name="pose_publishers_sampling_rate" default="-1" />
<arg name="pose_stamped_topic" default="" if="$(arg use_amcl)"/>
<arg name="pose_stamped_topic" default="$(arg localization_system_pose_stamped_topic)" unless="$(arg use_amcl)" />
<arg name="pose_stamped_with_covariance_pose_topic" default="/amcl_pose" if="$(arg use_amcl)" />
<arg name="pose_stamped_with_covariance_pose_topic" default="" unless="$(arg use_amcl)" />
<arg name="tf_lookup_timeout" default="0.2" />
<arg name="localization_poses_output_filename" default="$(arg world_rosbag_results_filename)_localization_poses.txt" if="$(arg record_localization_results_paths)" />
<arg name="localization_poses_output_filename" default="" unless="$(arg record_localization_results_paths)" />
<arg name="odom_only_poses_output_filename" default="$(arg world_rosbag_results_filename)_odometry_poses.txt" if="$(arg record_localization_results_paths)" />
<arg name="odom_only_poses_output_filename" default="" unless="$(arg record_localization_results_paths)" />
<arg name="ground_truth_poses_output_filename" default="$(arg world_rosbag_results_filename)_ground_truth_poses.txt" if="$(arg record_localization_results_paths)" />
<arg name="ground_truth_poses_output_filename" default="" unless="$(arg record_localization_results_paths)" />
<arg name="save_poses_timestamp" default="true" />
<arg name="save_poses_orientation_quaternion" default="true" />
<arg name="save_poses_orientation_vector" default="true" />
</include>
<!-- #################################################### rosbags ################################################ -->
<node pkg="rosbag" type="record" name="rosbag_record" args="$(arg record_rosbags_options) -O $(arg world_rosbag_filename).bag $(arg record_rosbags_topics)" if="$(arg record_rosbags)" />
<node pkg="rosbag" type="record" name="rosbag_record_results" args="$(arg record_rosbags_options) -O $(arg world_rosbag_results_filename).bag $(arg record_localization_results_topics)" if="$(arg record_localization_results)" />
<node pkg="rosbag" type="play" name="rosbag_play" args="--clock --pause --rate=$(arg play_rosbags_rate) $(arg world_rosbag_filename).bag $(arg world_rosbag_play_extra_filenames) $(arg play_rosbags_options)" if="$(arg play_rosbags)" />
<node pkg="robot_localization_tools" type="process_monitor.sh" name="process_monitor_drl" args="$(arg record_localization_system_process_name) $(arg world_rosbag_results_filename)_perf-stat.txt $(arg world_rosbag_results_filename)_hw_resources_usage_log 0.1" if="$(arg record_localization_system_resources_usage)" />
<node pkg="robot_localization_tools" type="save_parameters.bash" name="parameter_server_saver" args="$(arg world_rosbag_results_filename)_parameters.yaml 10" if="$(arg record_parameters)" />
<!-- #################################################### robot movement ################################################ -->
<include file="$(find robot_localization_tools)/launch/twist_publisher.launch" ns="dynamic_robot_localization" if="$(arg move_robot_on_path)" >
<arg name="yaml_path_file" default="$(arg robot_path)$(arg world_rosbag_path_suffix).yaml" />
<arg name="system_command_after_path_finished" default="$(arg system_command_after_path_finished)" />
</include>
<!-- #################################################### system inspection ################################################ -->
<node name="rviz" pkg="rviz" type="rviz" args="$(arg rviz_config)" if="$(arg show_rviz)" output="screen" />
<!-- ######################################################## 2D costmap ################################################## -->
<node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" output="screen" if="$(arg use_map_server)" >
<param name="frame_id" type="str" value="$(arg map_server_frame_id)" />
<remap from="map" to="$(arg map_server_topic)" />
</node>
<!-- ################################################ merge two LaserScan topics ########################################## -->
<node pkg="topic_tools" type="relay" name="relay_base_scan_to_tilt_scan" args="/guardian/laser_horizontal_back /guardian/laser_tilt_front" output="screen" if="$(arg relay_back_laser_to_front_laser)" />
<!-- #################################################### localization system ############################################# -->
<include file="$(find dynamic_robot_localization)/launch/dynamic_robot_localization_system.launch" if="$(arg use_dynamic_robot_localization)">
<arg name="ambient_pointcloud_topic" default="$(arg ambient_pointcloud_topic)" />
<arg name="reference_costmap_topic" default="$(arg reference_costmap_topic)" />
<arg name="reference_pointcloud_topic" default="$(arg reference_pointcloud_topic)" />
<arg name="yaml_configuration_filters_filename" default="$(arg yaml_configuration_filters_filename)" />
<arg name="yaml_configuration_pose_estimation_filename" default="$(arg yaml_configuration_pose_estimation_filename)" />
<arg name="yaml_configuration_tracking_filename" default="$(arg yaml_configuration_tracking_filename)" />
<arg name="yaml_configuration_recovery_filename" default="$(arg yaml_configuration_recovery_filename)" />
<arg name="robot_initial_pose_in_base_to_map" default="$(arg robot_initial_pose_in_base_to_map)" />
<arg name="robot_initial_pose_available" default="$(arg robot_initial_pose_available)" />
<arg name="robot_initial_x" default="$(arg robot_initial_x)" />
<arg name="robot_initial_y" default="$(arg robot_initial_y)" />
<arg name="robot_initial_z" default="$(arg robot_initial_z)" />
<arg name="robot_initial_roll" default="$(arg robot_initial_roll)" />
<arg name="robot_initial_pitch" default="$(arg robot_initial_pitch)" />
<arg name="robot_initial_yaw" default="$(arg robot_initial_yaw)" />
<arg name="use_laser_assembler" default="$(arg use_laser_assembler)" />
<arg name="laser_scan_topics" default="$(arg laser_scan_topics)" />
<arg name="min_range_cutoff_percentage_offset" default="$(arg min_range_cutoff_percentage_offset)" />
<arg name="max_range_cutoff_percentage_offset" default="$(arg max_range_cutoff_percentage_offset)" />
<arg name="number_of_tf_queries_for_spherical_interpolation" default="$(arg number_of_tf_queries_for_spherical_interpolation)" />
<arg name="dynamic_update_of_assembly_configuration_from_twist_topic" default="$(arg twist_topic)" />
<arg name="dynamic_update_of_assembly_configuration_from_odometry_topic" default="$(arg odometry_topic)" />
<arg name="dynamic_update_of_assembly_configuration_from_imu_topic" default="$(arg imu_topic)" />
<arg name="map_frame_id" default="$(arg map_frame_id)" />
<arg name="odom_frame_id" default="$(arg odom_frame_id)" />
<arg name="base_link_frame_id" default="$(arg base_link_frame_id)" />
<arg name="sensor_frame_id" default="$(arg sensor_frame_id)" />
<arg name="pose_stamped_publish_topic" default="$(arg localization_system_pose_stamped_topic)" />
<arg name="publish_tf_map_odom" default="$(arg publish_tf_map_odom)" />
<arg name="publish_pose_tf_rate" default="$(arg publish_pose_tf_rate)" />
<arg name="invert_tf_transform" default="$(arg invert_tf_transform)" />
<arg name="invert_tf_hierarchy" default="$(arg invert_tf_hierarchy)" />
<arg name="transform_pose_to_map_frame_id" default="$(arg transform_pose_to_map_frame_id)" />
<arg name="use_octomap_for_dynamic_map_update" default="$(arg use_octomap_for_dynamic_map_update)" />
<arg name="use_octomap_only_to_build_occupancy_grid" default="$(arg use_octomap_only_to_build_occupancy_grid)" />
<arg name="octomap_pointcloud_topic" default="$(arg octomap_pointcloud_topic)" />
<arg name="octomap_file" default="$(arg octomap_file)" />
<arg name="octomap_resolution" default="$(arg octomap_resolution)" />
<arg name="octomap_minimum_amount_of_time_between_ros_msg_publishing" default="$(arg octomap_minimum_amount_of_time_between_ros_msg_publishing)" />
<arg name="octomap_minimum_number_of_integrations_before_ros_msg_publishing" default="$(arg octomap_minimum_number_of_integrations_before_ros_msg_publishing)" />
<arg name="octomap_override_sensor_z" default="$(arg octomap_override_sensor_z)" />
<arg name="octomap_override_sensor_z_value" default="$(arg octomap_override_sensor_z_value)" />
<arg name="initial_2d_map_file" default="$(arg initial_2d_map_file)" />
<arg name="laser_assembly_frame" default="$(arg laser_assembly_frame)" />
<arg name="number_of_scans_to_assemble_per_cloud" default="$(arg number_of_scans_to_assemble_per_cloud)" />
<arg name="timeout_for_cloud_assembly" default="$(arg timeout_for_cloud_assembly)" />
<arg name="min_number_of_scans_to_assemble_per_cloud" default="$(arg min_number_of_scans_to_assemble_per_cloud)" />
<arg name="max_number_of_scans_to_assemble_per_cloud" default="$(arg max_number_of_scans_to_assemble_per_cloud)" />
<arg name="min_timeout_seconds_for_cloud_assembly" default="$(arg min_timeout_seconds_for_cloud_assembly)" />
<arg name="max_timeout_seconds_for_cloud_assembly" default="$(arg max_timeout_seconds_for_cloud_assembly)" />
<arg name="max_linear_velocity" default="$(arg max_linear_velocity)" />
<arg name="max_angular_velocity" default="$(arg max_angular_velocity)" />
<arg name="publish_last_pose_tf_timeout_seconds" default="$(arg publish_last_pose_tf_timeout_seconds)" />
<arg name="reference_pointcloud_available" default="$(arg reference_pointcloud_available)" />
<arg name="reference_pointcloud_type_3d" default="$(arg reference_pointcloud_type_3d)" />
<arg name="reference_pointcloud_update_mode" default="$(arg reference_pointcloud_update_mode)" />
<arg name="reference_pointcloud_filename" default="$(arg reference_pointcloud_filename)" if="$(arg use_6_dof)" />
<arg name="reference_pointcloud_preprocessed_save_filename" default="$(arg reference_pointcloud_preprocessed_save_filename)" />
<arg name="reference_pointcloud_keypoints_filename" default="$(arg reference_pointcloud_keypoints_filename)" if="$(arg load_point_features)" />
<arg name="reference_pointcloud_keypoints_save_filename" default="$(arg reference_pointcloud_keypoints_save_filename)" if="$(arg save_point_features)" />
<arg name="reference_pointcloud_descriptors_filename" default="$(arg reference_pointcloud_descriptors_filename)" if="$(arg load_point_features)" />
<arg name="reference_pointcloud_descriptors_save_filename" default="$(arg reference_pointcloud_descriptors_save_filename)" if="$(arg save_point_features)" />
</include>
<!-- ################################################# other localization systems ########################################## -->
<group if="$(arg use_odometry_as_localization_system)">
<!-- <node pkg="tf" type="static_transform_publisher" name="map_to_odom" args="$(arg robot_initial_x) $(arg robot_initial_y) $(arg robot_initial_z) $(arg robot_initial_yaw) 0 0 map odom 5" /> -->
<!-- map to odom publisher -->
<include file="$(find pose_to_tf_publisher)/launch/pose_to_tf_publisher.launch">
<arg name="initial_pose_in_base_to_map" default="$(arg robot_initial_pose_in_base_to_map)" />
<arg name="initial_x" default="$(arg robot_initial_x)" />
<arg name="initial_y" default="$(arg robot_initial_y)" />
<arg name="initial_z" default="$(arg robot_initial_z)" />
<arg name="initial_roll" default="$(arg robot_initial_roll)" />
<arg name="initial_pitch" default="$(arg robot_initial_pitch)" />
<arg name="initial_yaw" default="$(arg robot_initial_yaw)" />
<arg name="pose_with_covariance_stamped_topic" default="" />
<arg name="pose_stamped_topic" default="" />
<arg name="odometry_topic" default="" />
<arg name="map_frame_id" default="$(arg map_odom_only_frame_id)" />
<arg name="odom_frame_id" default="$(arg odom_frame_id)" />
<arg name="base_link_frame_id" default="$(arg base_link_frame_id)" />
<arg name="publish_rate" default="-30.0" />
<arg name="publish_initial_pose" default="true" />
<arg name="publish_last_pose_tf_timeout_seconds" default="-1.0" />
<arg name="invert_tf_transform" default="true" />
<arg name="invert_tf_hierarchy" default="true" />
<arg name="transform_pose_to_map_frame_id" default="true" />
<arg name="parameters_namespace" default="map_odom_only" />
</include>
</group>
<!-- asl_icp_mapper -->
<include file="$(find dynamic_robot_localization_tests)/launch/environments/asl_icp_mapper/ethzasl_icp_mapping_tracker.launch" if="$(arg use_ethzasl_icp_mapper)" >
<arg name="initial_x" default="$(arg robot_initial_x)" />
<arg name="initial_y" default="$(arg robot_initial_y)" />
<arg name="initial_z" default="$(arg robot_initial_z)" />
<arg name="initial_roll" default="$(arg robot_initial_roll)" />
<arg name="initial_pitch" default="$(arg robot_initial_pitch)" />
<arg name="initial_yaw" default="$(arg robot_initial_yaw)" />
<arg name="map_filename" default="$(arg reference_pointcloud_filename)" />
<arg name="min_registration_overlap" default="$(arg ethzasl_icp_mapper_min_registration_overlap)" />
<arg name="ethzasl_icp_mapper_icp_config_filename" default="$(arg ethzasl_icp_mapper_icp_config_filename)" />
</include>
<!-- simulated localization -->
<include file="$(find dynamic_robot_localization_tests)/launch/localization_systems/amcl_simulated.launch" if="$(arg use_amcl_simulated)" />
<!-- amcl localization -->
<include file="$(find dynamic_robot_localization_tests)/launch/localization_systems/amcl.launch" if="$(arg use_amcl)">
<arg name="robot_initial_x" default="$(arg robot_initial_x)" />
<arg name="robot_initial_y" default="$(arg robot_initial_y)" />
<arg name="robot_initial_yaw" default="$(arg robot_initial_yaw)" />
<arg name="laser_scan_topic" default="$(arg laser_scan_topic_amcl)" />
<arg name="map_frame_id" default="$(arg map_frame_id)" />
<arg name="odom_frame_id" default="$(arg odom_frame_id)" />
<arg name="base_link_frame_id" default="$(arg base_link_frame_id)" />
</include>
<!-- EFK Filter -->
<include file="$(find dynamic_robot_localization_tests)/launch/localization_systems/ekf.launch" if="$(arg use_ekf)" />
<!-- SLAM -->
<include file="$(find dynamic_robot_localization_tests)/launch/slam_systems/gmapping.launch" if="$(arg use_gmapping)" >
<arg name="base_link_frame_id" default="$(arg base_link_frame_id)" />
<arg name="laser_scan_topic" default="$(arg laser_scan_topic_amcl)" />
</include>
<include file="$(find dynamic_robot_localization_tests)/launch/slam_systems/hector.launch" if="$(arg use_hector)" >
<arg name="base_link_frame_id" default="$(arg base_link_frame_id)" />
<arg name="laser_scan_topic" default="$(arg laser_scan_topic_amcl)" />
</include>
<include file="$(find dynamic_robot_localization_tests)/launch/slam_systems/crsm.launch" if="$(arg use_crsm)" >
<arg name="base_link_frame_id" default="$(arg base_link_frame_id)" />
<arg name="laser_frame_id" default="$(arg sensor_frame_id)" />
<arg name="laser_scan_topic" default="$(arg laser_scan_topic_amcl)" />
</include>
<!-- ##################################################### localization plots ############################################## -->
<node pkg="hector_trajectory_server" type="hector_trajectory_server" name="hector_trajectory_server_gt" output="screen">
<param name="target_frame_name" value="$(arg localization_ground_truth_frame_id)" />
<param name="source_frame_name" value="$(arg base_link_frame_id)" />
<param name="trajectory_update_rate" value="30" />
<param name="trajectory_publish_rate" value="10" />
<remap from="trajectory" to="trajectory_gt" />
</node>
<node pkg="hector_trajectory_server" type="hector_trajectory_server" name="hector_trajectory_server" output="screen">
<param name="target_frame_name" value="$(arg map_frame_id)" />
<param name="source_frame_name" value="$(arg base_link_frame_id)" />
<param name="trajectory_update_rate" value="30" />
<param name="trajectory_publish_rate" value="10" />
</node>
<node pkg="hector_trajectory_server" type="hector_trajectory_server" name="hector_trajectory_server_drl" output="screen">
<param name="target_frame_name" value="$(arg map_frame_id)_drl" />
<param name="source_frame_name" value="$(arg base_link_frame_id)" />
<param name="trajectory_update_rate" value="30" />
<param name="trajectory_publish_rate" value="10" />
<remap from="trajectory" to="trajectory_drl" />
</node>
<node pkg="hector_trajectory_server" type="hector_trajectory_server" name="hector_trajectory_server_odom" output="screen">
<param name="target_frame_name" value="$(arg odom_frame_id)" />
<param name="source_frame_name" value="$(arg base_link_frame_id)" />
<param name="trajectory_update_rate" value="30" />
<param name="trajectory_publish_rate" value="10" />
<remap from="trajectory" to="trajectory_odom" />
</node>
<include file="$(find dynamic_robot_localization_tests)/launch/localization_plots.launch" if="$(arg show_plots)" />
<!-- ##################################################### navigation systems ############################################## -->
<!-- <include file="$(find dynamic_robot_localization_tests)/launch/navigation_systems/linear_navigation.launch" /> -->
<!-- <include file="$(find guardian_navigation)/launch/move_base.launch" /> -->
<!-- <include file="$(find guardian_navigation)/navigation_local/move_base_local.launch" /> -->
</launch>