-
Notifications
You must be signed in to change notification settings - Fork 76
/
params_velodyne_vlp16.yaml
executable file
·66 lines (59 loc) · 3.01 KB
/
params_velodyne_vlp16.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
sensor_height: 0.6
sensor_model: "VLP-16"
frame_patchwork: "acl_jackal2/velodyne"
# Extrinsics (Raw lidar coordinate -> Coordinate that is parallel to the X-Y plane of ground)
# But, not in use
extrinsic_trans: [0.0, 0.0, 0.0]
extrinsic_rot: [1, 0, 0,
0, 1, 0,
0, 0, 1]
patchwork:
mode: "czm"
verbose: false # To check effect of uprightness/elevation/flatness
visualize: true # Ground Likelihood Estimation is visualized
# Ground Plane Fitting parameters
num_iter: 3
num_lpr: 20
num_min_pts: 10
th_seeds: 0.2
th_dist: 0.075
max_r: 60.0
min_r: 0.6 # to consider vicinity of mobile plot form.
uprightness_thr: 0.707 # For uprightness. 45: 0.707 / 60: 0.866. The larger, the more conservative
# The points below the adaptive_seed_selection_margin * sensor_height are filtered
# For reject points caused by reflection or multipath problems.
# it should be lower than -1.0
adaptive_seed_selection_margin: -1.1
# It is not in the paper
# It is also not matched our philosophy, but it is employed to reject some FPs easily & intuitively.
# For patchwork, the global elevation threshold is only applied on Z3 and Z4
# In Kimera-Multi, the environments are mostly flat, so it is used.
using_global_elevation: true
# W.r.t sensor frame (That is, if it is 0.0, then the candidates whose z is higher than z height of 3D LiDAR sensor are rejected
global_elevation_threshold: 0.0
# 22.05.02 Update
# ATAT is the abbrev. for All-Terrain Automatic heighT estimator
# It automatically corrects the wrong sensor height input
ATAT:
ATAT_ON: true
# 22.05.02 Update
# IMPORTANT - `max_r_for_ATAT` affects the quality of the estimation of sensor height
# If it is too large, then the z-elevation values of the bins become more ambiguous
# If it is too small, there is a potential risk that does not include the cloud points in the vicinity of the vehicles/mobile robots
# Therefore, it should be set appropriately!
max_r_for_ATAT: 5.0
num_sectors_for_ATAT: 20
noise_bound: 0.2
uniform: # deprecated
num_rings: 16
num_sectors: 54
czm:
# 22.05.02 Update
# For usability, the MEANING OF THE ELEVATION THRESHOLDS IS CHANGED!!!!
# Original - the elevation w.r.t. to the sensor frame
# Modified - the elevation w.r.t. to the ground
# Thus, -sensor_height + elevation_threshold is the criteria.
# E.g. for the first ring, -1.723 (sensor height in the KITTI) + 0.523 = -1.2 becomes the criteria of the elevation filter
# That is, if the z-elevation of the bin is higher than -1.2, then the cloud points from the bin are rejected
elevation_thresholds: [0.523, 0.746, 0.879, 1.125] # For elevation. The size should be equal to flatness_thresholds vector
flatness_thresholds: [0.0005, 0.000725, 0.001, 0.001] # For flatness. The size should be equal to elevation_thresholds vector