-
Notifications
You must be signed in to change notification settings - Fork 192
/
cluttered_environments_dynamic_large_map_2d.yaml
70 lines (64 loc) · 3.65 KB
/
cluttered_environments_dynamic_large_map_2d.yaml
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
tracking_matchers:
transformation_estimation_approach: 'TransformationEstimation2D' # [ TransformationEstimation2D | TransformationEstimationDualQuaternion | TransformationEstimationLM | TransformationEstimationPointToPlane | TransformationEstimationPointToPlaneLLS | TransformationEstimationPointToPlaneLLSWeighted | TransformationEstimationPointToPlaneWeighted | TransformationEstimationSVD | TransformationEstimationSVDScale ]
ignore_height_corrections: true
correspondence_estimation_approach: 'CorrespondenceEstimationLookupTable'
correspondence_estimation_lookup_table: # Can be overridden in child namespaces | Only used if -> correspondence_estimation_approach: CorrespondenceEstimationOrganizedProjection
map_cell_resolution: 0.02 # Cell size in meters
map_margin_x: 1.0 # Margin around map data with extra lookup cells
map_margin_y: 1.0 # Margin around map data with extra lookup cells
map_margin_z: 0.0 # Margin around map data with extra lookup cells
sensor_cell_resolution: 0.02 # Cell size in meters
sensor_margin_x: 1.0 # Margin around map data with extra lookup cells
sensor_margin_y: 1.0 # Margin around map data with extra lookup cells
sensor_margin_z: 0.0 # Margin around map data with extra lookup cells
point_matchers:
# iterative_closest_point:
iterative_closest_point_2d:
# iterative_closest_point_non_linear:
# iterative_closest_point_generalized:
# normal_distributions_transform_2d:
convergence_time_limit_seconds: 0.150
max_correspondence_distance: 0.5
transformation_epsilon: 0.000001
euclidean_fitness_epsilon: 0.000001
max_number_of_registration_iterations: 150
max_number_of_ransac_iterations: 0
ransac_outlier_rejection_threshold: 0.035
match_only_keypoints: false
display_cloud_aligment: false
maximum_number_of_displayed_correspondences: 0
# gicp
rotation_epsilon: 0.002
correspondence_randomness: 50
maximum_optimizer_iterations: 100
use_reciprocal_correspondences: false
# ndt_2d
grid_center_x: 10.0
grid_center_y: 5.0
grid_step_x: 0.05
grid_step_y: 0.05
grid_extent_x: 20.0
grid_extent_y: 20.0
grid_optimization_step_size_x: 0.05
grid_optimization_step_size_y: 0.05
grid_optimization_step_size_theta: 0.025
outlier_detectors:
euclidean_outlier_detector:
max_inliers_distance: 0.05
aligned_pointcloud_outliers_publish_topic: 'aligned_pointcloud_outliers'
aligned_pointcloud_inliers_publish_topic: 'aligned_pointcloud_inliers'
#cloud_analyzers:
# compute_inliers_angular_distribution: true
# compute_outliers_angular_distribution: true
# angular_distribution_analyzer:
# number_of_angular_bins: 180
transformation_validators:
euclidean_transformation_validator:
max_transformation_angle: 0.7
max_transformation_distance: 0.5
max_new_pose_diff_angle: 1.1
max_new_pose_diff_distance: 0.7
max_root_mean_square_error: 0.04
max_outliers_percentage: 0.6
min_inliers_angular_distribution: 0.125
max_outliers_angular_distribution: 0.875