Skip to content

Commit 4c7c240

Browse files
committed
refactor(ndt_scan_matcher): hierarchize parameters
Signed-off-by: Yamato Ando <yamato.ando@tier4.jp>
1 parent 9ba76c6 commit 4c7c240

File tree

1 file changed

+83
-73
lines changed

1 file changed

+83
-73
lines changed
Original file line numberDiff line numberDiff line change
@@ -1,102 +1,112 @@
11
/**:
22
ros__parameters:
3-
# Vehicle reference frame
4-
base_frame: "base_link"
3+
frame:
4+
# Vehicle reference frame
5+
base_frame: "base_link"
56

6-
# NDT reference frame
7-
ndt_base_frame: "ndt_base_link"
7+
# NDT reference frame
8+
ndt_base_frame: "ndt_base_link"
89

9-
# map frame
10-
map_frame: "map"
10+
# Map frame
11+
map_frame: "map"
1112

12-
# Subscriber queue size
13-
input_sensor_points_queue_size: 1
1413

15-
# The maximum difference between two consecutive
16-
# transformations in order to consider convergence
17-
trans_epsilon: 0.01
14+
ndt:
15+
# The maximum difference between two consecutive
16+
# transformations in order to consider convergence
17+
trans_epsilon: 0.01
1818

19-
# The newton line search maximum step length
20-
step_size: 0.1
19+
# The newton line search maximum step length
20+
step_size: 0.1
2121

22-
# The ND voxel grid resolution
23-
resolution: 2.0
22+
# The ND voxel grid resolution
23+
resolution: 2.0
2424

25-
# The number of iterations required to calculate alignment
26-
max_iterations: 30
25+
# The number of iterations required to calculate alignment
26+
max_iterations: 30
2727

28-
# Converged param type
29-
# 0=TRANSFORM_PROBABILITY, 1=NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD
30-
converged_param_type: 1
28+
# Number of threads used for parallel computing
29+
num_threads: 4
3130

32-
# If converged_param_type is 0
33-
# Threshold for deciding whether to trust the estimation result
34-
converged_param_transform_probability: 3.0
31+
regularization:
32+
enable: false
3533

36-
# If converged_param_type is 1
37-
# Threshold for deciding whether to trust the estimation result
38-
converged_param_nearest_voxel_transformation_likelihood: 2.3
34+
# Regularization scale factor
35+
scale_factor: 0.01
3936

40-
# The number of particles to estimate initial pose
41-
initial_estimate_particles_num: 200
4237

43-
# The number of initial random trials in the TPE (Tree-Structured Parzen Estimator).
44-
# This value should be equal to or less than 'initial_estimate_particles_num' and more than 0.
45-
# If it is equal to 'initial_estimate_particles_num', the search will be the same as a full random search.
46-
n_startup_trials: 20
38+
initial_pose_estimation:
39+
# The number of particles to estimate initial pose
40+
particles_num: 200
4741

48-
# Tolerance of timestamp difference between current time and sensor pointcloud. [sec]
49-
lidar_topic_timeout_sec: 1.0
42+
# The number of initial random trials in the TPE (Tree-Structured Parzen Estimator).
43+
# This value should be equal to or less than 'initial_estimate_particles_num' and more than 0.
44+
# If it is equal to 'initial_estimate_particles_num', the search will be the same as a full random search.
45+
n_startup_trials: 20
5046

51-
# Tolerance of timestamp difference between initial_pose and sensor pointcloud. [sec]
52-
initial_pose_timeout_sec: 1.0
5347

54-
# Tolerance of distance difference between two initial poses used for linear interpolation. [m]
55-
initial_pose_distance_tolerance_m: 10.0
48+
validation:
49+
# Tolerance of timestamp difference between current time and sensor pointcloud. [sec]
50+
lidar_topic_timeout_sec: 1.0
5651

57-
# The execution time which means probably NDT cannot matches scans properly. [ms]
58-
critical_upper_bound_exe_time_ms: 100.0
52+
# Tolerance of timestamp difference between initial_pose and sensor pointcloud. [sec]
53+
initial_pose_timeout_sec: 1.0
5954

60-
# Number of threads used for parallel computing
61-
num_threads: 4
55+
# Tolerance of distance difference between two initial poses used for linear interpolation. [m]
56+
initial_pose_distance_tolerance_m: 10.0
6257

63-
# The covariance of output pose
64-
# Note that this covariance matrix is empirically derived
65-
output_pose_covariance:
66-
[
67-
0.0225, 0.0, 0.0, 0.0, 0.0, 0.0,
68-
0.0, 0.0225, 0.0, 0.0, 0.0, 0.0,
69-
0.0, 0.0, 0.0225, 0.0, 0.0, 0.0,
70-
0.0, 0.0, 0.0, 0.000625, 0.0, 0.0,
71-
0.0, 0.0, 0.0, 0.0, 0.000625, 0.0,
72-
0.0, 0.0, 0.0, 0.0, 0.0, 0.000625,
73-
]
58+
# The execution time which means probably NDT cannot matches scans properly. [ms]
59+
critical_upper_bound_exe_time_ms: 100.0
7460

75-
# 2D Real-time covariance estimation with multiple searches (output_pose_covariance is the minimum value)
76-
use_covariance_estimation: false
61+
score_estimation:
62+
# Converged param type
63+
# 0=TRANSFORM_PROBABILITY, 1=NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD
64+
converged_param_type: 1
7765

78-
# Offset arrangement in covariance estimation [m]
79-
# initial_pose_offset_model_x & initial_pose_offset_model_y must have the same number of elements.
80-
initial_pose_offset_model_x: [0.0, 0.0, 0.5, -0.5, 1.0, -1.0]
81-
initial_pose_offset_model_y: [0.5, -0.5, 0.0, 0.0, 0.0, 0.0]
66+
# If converged_param_type is 0
67+
# Threshold for deciding whether to trust the estimation result
68+
converged_param_transform_probability: 3.0
8269

83-
# Regularization switch
84-
regularization_enabled: false
70+
# If converged_param_type is 1
71+
# Threshold for deciding whether to trust the estimation result
72+
converged_param_nearest_voxel_transformation_likelihood: 2.3
8573

86-
# Regularization scale factor
87-
regularization_scale_factor: 0.01
74+
# Scan matching score based on no ground LiDAR scan
75+
no_ground_points:
76+
enable: false
8877

89-
# Dynamic map loading distance
90-
dynamic_map_loading_update_distance: 20.0
78+
# If lidar_point.z - base_link.z <= this threshold , the point will be removed
79+
z_margin_for_ground_removal: 0.8
9180

92-
# Dynamic map loading loading radius
93-
dynamic_map_loading_map_radius: 150.0
9481

95-
# Radius of input LiDAR range (used for diagnostics of dynamic map loading)
96-
lidar_radius: 100.0
82+
covariance:
83+
# The covariance of output pose
84+
# Note that this covariance matrix is empirically derived
85+
output_pose_covariance:
86+
[
87+
0.0225, 0.0, 0.0, 0.0, 0.0, 0.0,
88+
0.0, 0.0225, 0.0, 0.0, 0.0, 0.0,
89+
0.0, 0.0, 0.0225, 0.0, 0.0, 0.0,
90+
0.0, 0.0, 0.0, 0.000625, 0.0, 0.0,
91+
0.0, 0.0, 0.0, 0.0, 0.000625, 0.0,
92+
0.0, 0.0, 0.0, 0.0, 0.0, 0.000625,
93+
]
9794

98-
# A flag for using scan matching score based on no ground LiDAR scan
99-
estimate_scores_by_no_ground_points: false
95+
# 2D Real-time covariance estimation with multiple searches (output_pose_covariance is the minimum value)
96+
covariance_estimation:
97+
enable: false
10098

101-
# If lidar_point.z - base_link.z <= this threshold , the point will be removed
102-
z_margin_for_ground_removal: 0.8
99+
# Offset arrangement in covariance estimation [m]
100+
# initial_pose_offset_model_x & initial_pose_offset_model_y must have the same number of elements.
101+
initial_pose_offset_model_x: [0.0, 0.0, 0.5, -0.5, 1.0, -1.0]
102+
initial_pose_offset_model_y: [0.5, -0.5, 0.0, 0.0, 0.0, 0.0]
103+
104+
dynamic_map_loading:
105+
# Dynamic map loading distance
106+
update_distance: 20.0
107+
108+
# Dynamic map loading loading radius
109+
map_radius: 150.0
110+
111+
# Radius of input LiDAR range (used for diagnostics of dynamic map loading)
112+
lidar_radius: 100.0

0 commit comments

Comments
 (0)