-
Notifications
You must be signed in to change notification settings - Fork 0
/
tracking_cluttered_environments_dynamic_large_map_2d.yaml
114 lines (104 loc) · 4.12 KB
/
tracking_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
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
normal_estimators:
reference_pointcloud:
display_normals: false
display_occupancy_grid_pointcloud: false
flip_normals_using_occupancy_grid_analysis: true
occupancy_grid_analysis_radius_resolution_percentage: 4.0
normal_estimator_sac:
model_type: 'SACMODEL_LINE'
method_type: 'SAC_RANSAC'
inlier_distance_threshold: 0.07
max_iterations: 50
sac_termination_probability: 0.99
optimize_coefficients: true
min_model_radius: -1.0
max_model_radius: -1.0
random_samples_max_k: 0
random_samples_max_radius: 0.07
minimum_inliers_percentage: 0.5
ambient_pointcloud:
compute_normals_when_tracking_pose: false
compute_normals_when_recovering_pose_tracking: false
compute_normals_when_estimating_initial_pose: true
display_normals: false
normal_estimator_sac:
model_type: 'SACMODEL_LINE'
method_type: 'SAC_RANSAC'
inlier_distance_threshold: 0.07
max_iterations: 50
sac_termination_probability: 0.99
optimize_coefficients: true
min_model_radius: -1.0
max_model_radius: -1.0
random_samples_max_k: 0
random_samples_max_radius: 0.07
minimum_inliers_percentage: 0.5
curvature_estimators:
reference_pointcloud:
principal_curvatures_estimation:
search_k: 0
search_radius: 0.07
curvature_type: 'CURVATURE_TYPE_MEAN'
update_normals_with_principal_component_directions: false
ambient_pointcloud:
principal_curvatures_estimation:
search_k: 0
search_radius: 0.07
curvature_type: 'CURVATURE_TYPE_MEAN'
update_normals_with_principal_component_directions: false
tracking_matchers:
ignore_height_corrections: false
# pose_tracking_timeout: 2.0
# pose_tracking_minimum_number_of_failed_registrations_since_last_valid_pose: 5
point_matchers:
# iterative_closest_point:
iterative_closest_point_2d:
# iterative_closest_point_non_linear:
# iterative_closest_point_with_normals:
# iterative_closest_point_generalized:
# normal_distributions_transform_2d:
convergence_time_limit_seconds: 0.125
max_correspondence_distance: 0.2
transformation_epsilon: 1e-6
euclidean_fitness_epsilon: 1e-6
max_number_of_registration_iterations: 100
max_number_of_ransac_iterations: 100
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.07
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.9
max_root_mean_square_error: 0.1
max_outliers_percentage: 0.85
min_inliers_angular_distribution: 0.07
max_outliers_angular_distribution: 0.875