forked from Ikhyeon-Cho/FastDEM
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathglobal_mapping.yaml
More file actions
92 lines (81 loc) · 2.63 KB
/
global_mapping.yaml
File metadata and controls
92 lines (81 loc) · 2.63 KB
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
# FastDEM ROS Configuration
topics:
input_scans: ["/points"] # multi-sensor: ["/lidar/points", "/realsense/points"]
publish_rate: 5.0 # [Hz] local view around robot
global_publish_rate: 1.0 # [Hz] full global map
post_process_rate: 1.0 # [Hz] 0 = service-only (no auto timer)
tf:
base_frame: "base_link"
map_frame: "map"
max_wait_time: 0.1 # [sec]
max_stale_time: 0.1 # [sec]
map:
width: 200.0 # [m]
height: 200.0 # [m]
resolution: 0.1 # [m/cell]
point_filter:
z_min: -0.5 # [m] min height in base frame
z_max: 2.0 # [m] max height in base frame
range_min: 0.5 # [m] min range from sensor
range_max: 20.0 # [m] max range from sensor
logger:
level: "info" # info, warn, error, debug
# ─── Mapping Pipeline ───────────────────────────────
mapping:
mode: "global" # local | global
type: "kalman_filter" # kalman_filter | p2_quantile
kalman:
min_variance: 0.0001 # [m²]
max_variance: 0.01 # [m²]
process_noise: 0.0 # [m²]
p2:
dn0: 0.0
dn1: 0.16
dn2: 0.50
dn3: 0.84
dn4: 1.0
elevation_marker: 3
max_sample_count: 0
sensor_model:
type: "lidar" # constant | lidar | rgbd
lidar:
range_noise: 0.02 # [m] σ_r
angular_noise: 0.001 # [rad] σ_θ
rgbd:
normal_a: 0.001 # [m] base depth noise
normal_b: 0.002 # [m⁻¹] quadratic coefficient
normal_c: 0.4 # [m] optimal depth
lateral_factor: 0.001 # lateral noise factor
constant:
uncertainty: 0.03 # [m] σ
# ─── Post-processing ───────────────────────────────
raycasting:
enabled: true
height_conflict_threshold: 0.05 # [m]
log_odds_observed: 0.4
log_odds_ghost: 0.2
log_odds_max: 2.0
clear_threshold: -1.0
inpainting:
enabled: false
max_iterations: 3
min_valid_neighbors: 2
uncertainty_fusion:
enabled: false
search_radius: 0.15 # [m]
spatial_sigma: 0.05 # [m]
quantile_lower: 0.01
quantile_upper: 0.99
min_valid_neighbors: 3
feature_extraction:
enabled: false
analysis_radius: 0.3 # [m]
min_valid_neighbors: 4
step_lower_percentile: 0.05
step_upper_percentile: 0.95
# ─── Visualization ────────────────────────────────
visualization:
feature_extraction:
normals:
arrow_length: 0.15 # [m] normal vector line length
stride: 3 # cell stride (1=all, 2=every 2nd, ...)