You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
checker_layer: 'traversability'# layer name for checking the validity of the cell.
10
+
min_filter_size: 5# size of the filter for min filter.
11
+
min_filter_iteration: 3# number of iterations for min filter.
12
+
initialized_variance: 10.0# initial variance for each cell.
13
+
resolution: 0.1# resolution in m.
14
+
map_length: 20.0# map's size in m.
15
+
sensor_noise_factor: 0.05# point's noise is sensor_noise_factor*z^2 (z is distance from sensor).
16
+
mahalanobis_thresh: 2.0# points outside this distance is outlier.
17
+
outlier_variance: 0.01# if point is outlier, add this value to the cell.
18
+
drift_compensation_variance_inler: 0.05# cells under this value is used for drift compensation.
19
+
max_drift: 0.1# drift compensation happens only the drift is smaller than this value (for safety)
20
+
drift_compensation_alpha: 0.1# drift compensation alpha for smoother update of drift compensation
21
+
time_variance: 0.0001# add this value when update_variance is called.
22
+
max_variance: 100.0# maximum variance for each cell.
23
+
initial_variance: 1000.0# initial variance for each cell.
24
+
traversability_inlier: 0.9# cells with higher traversability are used for drift compensation.
25
+
dilation_size: 3# dilation filter size before traversability filter.
26
+
wall_num_thresh: 20# if there are more points than this value, only higher points than the current height are used to make the wall more sharp.
27
+
min_height_drift_cnt: 100# drift compensation only happens if the valid cells are more than this number.
28
+
position_noise_thresh: 0.01# if the position change is bigger than this value, the drift compensation happens.
29
+
orientation_noise_thresh: 0.01# if the orientation change is bigger than this value, the drift compensation happens.
30
+
position_lowpass_alpha: 0.2# lowpass filter alpha used for detecting movements.
31
+
orientation_lowpass_alpha: 0.2# lowpass filter alpha used for detecting movements.
32
+
min_valid_distance: 0.5# points with shorter distance will be filtered out.
33
+
max_height_range: 1.0# points higher than this value from sensor will be filtered out to disable ceiling.
34
+
ramped_height_range_a: 0.3# if z > max(d - ramped_height_range_b, 0) * ramped_height_range_a + ramped_height_range_c, reject.
35
+
ramped_height_range_b: 1.0# if z > max(d - ramped_height_range_b, 0) * ramped_height_range_a + ramped_height_range_c, reject.
36
+
ramped_height_range_c: 0.2# if z > max(d - ramped_height_range_b, 0) * ramped_height_range_a + ramped_height_range_c, reject.
37
+
update_variance_fps: 5.0# fps for updating variance.
38
+
update_pose_fps: 10.0# fps for updating pose and shift the center of map.
39
+
time_interval: 0.1# Time layer is updated with this interval.
40
+
map_acquire_fps: 5.0# Raw map is fetched from GPU memory in this fps.
41
+
publish_statistics_fps: 1.0# Publish statistics topic in this fps.
42
+
43
+
max_ray_length: 10.0# maximum length for ray tracing.
44
+
cleanup_step: 0.1# subtitute this value from validity layer at visibiltiy cleanup.
45
+
cleanup_cos_thresh: 0.1# subtitute this value from validity layer at visibiltiy cleanup.
46
+
47
+
safe_thresh: 0.7# if traversability is smaller, it is counted as unsafe cell.
48
+
safe_min_thresh: 0.4# polygon is unsafe if there exists lower traversability than this.
49
+
max_unsafe_n: 10# if the number of cells under safe_thresh exceeds this value, polygon is unsafe.
50
+
51
+
overlap_clear_range_xy: 4.0# xy range [m] for clearing overlapped area. this defines the valid area for overlap clearance. (used for multi floor setting)
52
+
overlap_clear_range_z: 2.0# z range [m] for clearing overlapped area. cells outside this range will be cleared. (used for multi floor setting)
53
+
pose_topic: '/odom'
54
+
map_frame: 'odom'# The map frame where the odometry source uses.
55
+
base_frame: 'base_link'# The robot's base frame. This frame will be a center of the map.
56
+
corrected_map_frame: 'odom'
57
+
58
+
59
+
60
+
#### Feature toggles ########
61
+
enable_edge_sharpen: true
62
+
enable_visibility_cleanup: true
63
+
enable_drift_compensation: true
64
+
enable_overlap_clearance: true
65
+
enable_pointcloud_publishing: false
66
+
enable_drift_corrected_TF_publishing: false
67
+
enable_normal_color: true # If true, the map contains 'color' layer corresponding to normal. Add 'color' layer to the publishers setting if you want to visualize.
68
+
69
+
70
+
#### Traversability filter ########
71
+
use_chainer: false # Use chainer as a backend of traversability filter or pytorch. If false, it uses pytorch. pytorch requires ~2GB more GPU memory compared to chainer but runs faster.
72
+
weight_file: '/share/elevation_mapping_cupy/config/core/weights.dat'# Weight file for traversability filter
73
+
plugin_config_file: '/share/elevation_mapping_cupy/config/core/plugin_config.yaml'# Configuration file for the plugin.
74
+
#### Upper bound ########
75
+
use_only_above_for_upper_bound: false
76
+
77
+
#### Initializer ########
78
+
initialize_method: 'linear'# Choose one from 'nearest', 'linear', 'cubic'
79
+
initialize_frame_id: ['base_footprint'] # One tf (like ['footprint'] ) initializes a square around it.
80
+
initialize_tf_offset: [0.0, 0.0, 0.0, 0.0] # z direction. Should be same number as initialize_frame_id.
81
+
dilation_size_initialize: 2# dilation size after the init.
82
+
initialize_tf_grid_size: 0.5# This is not used if number of tf is more than 3.
83
+
use_initializer_at_start: true # Use initializer when the node starts.
84
+
85
+
#### Default Plugins ########
86
+
87
+
pointcloud_channel_fusions:
88
+
rgb: 'color'# 'color' fusion is used for the 'rgb' channel
89
+
default: 'average'# 'average' fusion is used for channels not listed here
90
+
91
+
image_channel_fusions:
92
+
rgb: 'color'# 'color' fusion is used for the 'rgb' channel
93
+
default: 'exponential'# 'exponential' fusion is used for channels not listed here
94
+
feat_.*: 'exponential'# 'exponential' fusion is also used for any channel starting with 'feat_' Regular expressions can be used for channel names
Copy file name to clipboardExpand all lines: elevation_mapping_cupy/config/core/core_param.yaml
+19-17Lines changed: 19 additions & 17 deletions
Original file line number
Diff line number
Diff line change
@@ -1,6 +1,7 @@
1
1
elevation_mapping:
2
2
ros__parameters:
3
-
#### Basic parameters ########
3
+
#### Basic parameters ########
4
+
enable_normal_arrow_publishing: false
4
5
cell_n: 40000# number of cells in the map.
5
6
data_type: 'float32'# data type for the map.
6
7
average_weight: 0.5
@@ -10,7 +11,7 @@ elevation_mapping:
10
11
min_filter_iteration: 3# number of iterations for min filter.
11
12
initialized_variance: 10.0# initial variance for each cell.
12
13
resolution: 0.1# resolution in m.
13
-
map_length: 20.0# map's size in m.
14
+
map_length: 20.0# map's size in m.
14
15
sensor_noise_factor: 0.05# point's noise is sensor_noise_factor*z^2 (z is distance from sensor).
15
16
mahalanobis_thresh: 2.0# points outside this distance is outlier.
16
17
outlier_variance: 0.01# if point is outlier, add this value to the cell.
@@ -63,8 +64,8 @@ elevation_mapping:
63
64
enable_overlap_clearance: true
64
65
enable_pointcloud_publishing: false
65
66
enable_drift_corrected_TF_publishing: false
66
-
enable_normal_color: false# If true, the map contains 'color' layer corresponding to normal. Add 'color' layer to the publishers setting if you want to visualize.
67
-
enable_normal: false
67
+
enable_normal_color: true# If true, the map contains 'color' layer corresponding to normal. Add 'color' layer to the publishers setting if you want to visualize.
68
+
enable_normal: true
68
69
69
70
#### Traversability filter ########
70
71
use_chainer: false # Use chainer as a backend of traversability filter or pytorch. If false, it uses pytorch. pytorch requires ~2GB more GPU memory compared to chainer but runs faster.
0 commit comments