|
| 1 | +# 22.05.02 Update |
| 2 | +# `sensor_height` denotes the elevation of the origin of the point cloud "with respect to the ground" |
| 3 | +# So, it mostly have a positive value |
| 4 | +# Note that if `patchwork/ATAT/ATAT_ON` is set to be true, the sensor_height is auto-calibrated |
| 5 | +# Nevertheless, the `sensor_height` should be set appropriately! |
| 6 | +sensor_height: 0.7 |
| 7 | +save_flag: false |
| 8 | +sensor_model: "OS1-64" |
| 9 | + |
| 10 | +# Extrinsics (Raw lidar coordinate -> Coordinate that is parallel to the X-Y plane of ground) |
| 11 | +# But, not in use |
| 12 | +extrinsic_trans: [0.0, 0.0, 0.0] |
| 13 | +extrinsic_rot: [1, 0, 0, |
| 14 | + 0, 1, 0, |
| 15 | + 0, 0, 1] |
| 16 | +patchwork: |
| 17 | + mode: "czm" |
| 18 | + verbose: false # To check effect of uprightness/elevation/flatness |
| 19 | + visualize: true # Ground Likelihood Estimation is visualized |
| 20 | + # Ground Plane Fitting parameters |
| 21 | + num_iter: 3 |
| 22 | + num_lpr: 20 |
| 23 | + num_min_pts: 10 |
| 24 | + th_seeds: 0.3 |
| 25 | + th_dist: 0.125 |
| 26 | + max_r: 80.0 |
| 27 | + min_r: 1.0 # to consider vicinity of mobile plot form. |
| 28 | + uprightness_thr: 0.707 # For uprightness. 45: 0.707 / 60: 0.866. The larger, the more conservative |
| 29 | + |
| 30 | + # The points below the adaptive_seed_selection_margin * sensor_height are filtered |
| 31 | + # Tor rejecti points caused by reflection or multipath problems. |
| 32 | + # it should be lower than -1.0 |
| 33 | + adaptive_seed_selection_margin: -1.1 |
| 34 | + |
| 35 | + # It is not in the paper |
| 36 | + # It is also not matched our philosophy, but it is employed to reject some FPs easily & intuitively. |
| 37 | + # For patchwork, the global elevation threshold is only applied on Z3 and Z4 |
| 38 | + using_global_elevation: true |
| 39 | + # 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 |
| 40 | + global_elevation_threshold: -0.25 |
| 41 | + |
| 42 | + # 22.05.02 Update |
| 43 | + # ATAT is the abbrev. for All-Terrain Automatic heighT estimator |
| 44 | + # It automatically corrects the wrong sensor height input |
| 45 | + ATAT: |
| 46 | + ATAT_ON: true |
| 47 | + # 22.05.02 Update |
| 48 | + # IMPORTANT - `max_r_for_ATAT` affects the quality of the estimation of sensor height |
| 49 | + # If it is too large, then the z-elevation values of the bins become more ambiguous |
| 50 | + # 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 |
| 51 | + # Therefore, it should be set appropriately! |
| 52 | + max_r_for_ATAT: 5.0 |
| 53 | + num_sectors_for_ATAT: 20 |
| 54 | + noise_bound: 0.2 |
| 55 | + |
| 56 | + uniform: # deprecated |
| 57 | + num_rings: 16 |
| 58 | + num_sectors: 54 |
| 59 | + czm: |
| 60 | + # Note that `num_zones` == size of `num_sectors_each_zone` == size of `num_rings_each_zone` == size of `min_ranges` - 1 |
| 61 | + # To divide zones, max_r, min_r, and min_ranges are utilized |
| 62 | + num_zones: 4 |
| 63 | + num_sectors_each_zone: [16, 32 ,54, 32] |
| 64 | + num_rings_each_zone: [2, 4, 4, 4] |
| 65 | + # Note that `min_r` == `min_ranges_each_zone`[0]! |
| 66 | + min_ranges_each_zone: [2.7, 12.3625, 22.025, 41.35] |
| 67 | + # The elevation_thresholds are with respect to the sensor frame |
| 68 | + # Thus, actually (sensor_height - threshold_value) is the maximum ground height. |
| 69 | + # For instance, for the first ring, 1.723 - 1.2 = 0.523 is acceptable, maximum ground height |
| 70 | + # Note that the size of below parameters are indepentent to `num_zones`! |
| 71 | + elevation_thresholds: [0.175, 0.175, 0.20, 0.25] # For elevation. The size should be equal to flatness_thresholds vector |
| 72 | + flatness_thresholds: [0.0, 0.000125, 0.000185, 0.000185] # For flatness. The size should be equal to elevation_thresholds vector |
| 73 | + |
| 74 | + |
| 75 | + |
0 commit comments