Skip to content

Commit 6e01476

Browse files
committed
Added g1 parameters
1 parent 20a8a26 commit 6e01476

File tree

4 files changed

+172
-0
lines changed

4 files changed

+172
-0
lines changed
Lines changed: 89 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,89 @@
1+
#### Basic parameters ########
2+
resolution: 0.04 # resolution in m.
3+
map_length: 8 # map's size in m.
4+
sensor_noise_factor: 0.05 # point's noise is sensor_noise_factor*z^2 (z is distance from sensor).
5+
mahalanobis_thresh: 2.0 # points outside this distance is outlier.
6+
outlier_variance: 0.01 # if point is outlier, add this value to the cell.
7+
drift_compensation_variance_inler: 0.05 # cells under this value is used for drift compensation.
8+
max_drift: 0.1 # drift compensation happens only the drift is smaller than this value (for safety)
9+
drift_compensation_alpha: 0.1 # drift compensation alpha for smoother update of drift compensation
10+
time_variance: 0.0001 # add this value when update_variance is called.
11+
max_variance: 100.0 # maximum variance for each cell.
12+
initial_variance: 1000.0 # initial variance for each cell.
13+
traversability_inlier: 0.9 # cells with higher traversability are used for drift compensation.
14+
dilation_size: 3 # dilation filter size before traversability filter.
15+
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.
16+
min_height_drift_cnt: 100 # drift compensation only happens if the valid cells are more than this number.
17+
position_noise_thresh: 0.01 # if the position change is bigger than this value, the drift compensation happens.
18+
orientation_noise_thresh: 0.01 # if the orientation change is bigger than this value, the drift compensation happens.
19+
position_lowpass_alpha: 0.2 # lowpass filter alpha used for detecting movements.
20+
orientation_lowpass_alpha: 0.2 # lowpass filter alpha used for detecting movements.
21+
min_valid_distance: 0.5 # points with shorter distance will be filtered out.
22+
max_height_range: 1.0 # points higher than this value from sensor will be filtered out to disable ceiling.
23+
ramped_height_range_a: 0.3 # if z > max(d - ramped_height_range_b, 0) * ramped_height_range_a + ramped_height_range_c, reject.
24+
ramped_height_range_b: 1.0 # if z > max(d - ramped_height_range_b, 0) * ramped_height_range_a + ramped_height_range_c, reject.
25+
ramped_height_range_c: 0.2 # if z > max(d - ramped_height_range_b, 0) * ramped_height_range_a + ramped_height_range_c, reject.
26+
update_variance_fps: 5.0 # fps for updating variance.
27+
update_pose_fps: 10.0 # fps for updating pose and shift the center of map.
28+
time_interval: 0.1 # Time layer is updated with this interval.
29+
map_acquire_fps: 5.0 # Raw map is fetched from GPU memory in this fps.
30+
publish_statistics_fps: 1.0 # Publish statistics topic in this fps.
31+
32+
max_ray_length: 10.0 # maximum length for ray tracing.
33+
cleanup_step: 0.1 # subtitute this value from validity layer at visibiltiy cleanup.
34+
cleanup_cos_thresh: 0.1 # subtitute this value from validity layer at visibiltiy cleanup.
35+
36+
safe_thresh: 0.7 # if traversability is smaller, it is counted as unsafe cell.
37+
safe_min_thresh: 0.4 # polygon is unsafe if there exists lower traversability than this.
38+
max_unsafe_n: 10 # if the number of cells under safe_thresh exceeds this value, polygon is unsafe.
39+
40+
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)
41+
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)
42+
43+
map_frame: 'map' # The map frame where the odometry source uses.
44+
base_frame: 'body' # The robot's base frame. This frame will be a center of the map.
45+
corrected_map_frame: 'odom_corrected'
46+
47+
#### Feature toggles ########
48+
enable_edge_sharpen: true
49+
enable_visibility_cleanup: true
50+
enable_drift_compensation: true
51+
enable_overlap_clearance: true
52+
enable_pointcloud_publishing: false
53+
enable_drift_corrected_TF_publishing: false
54+
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.
55+
56+
#### Traversability filter ########
57+
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.
58+
weight_file: '$(rospack find elevation_mapping_cupy)/config/core/weights.dat' # Weight file for traversability filter
59+
60+
#### Upper bound ########
61+
use_only_above_for_upper_bound: false
62+
63+
#### Plugins ########
64+
# plugin_config_file: '$(rospack find elevation_mapping_cupy)/config/anymal_plugin_config.yaml'
65+
66+
#### Publishers ########
67+
# topic_name:
68+
# layers: # Choose from 'elevation', 'variance', 'traversability', 'time', 'normal_x', 'normal_y', 'normal_z', 'color', plugin_layer_names
69+
# basic_layers: # basic_layers for valid cell computation (e.g. Rviz): Choose a subset of `layers`.
70+
# fps: # Publish rate. Use smaller value than `map_acquire_fps`.
71+
72+
# publishers:
73+
# elevation_map_raw:
74+
# layers: ['elevation', 'traversability', 'variance']
75+
# basic_layers: ['elevation', 'traversability']
76+
# fps: 5.0
77+
78+
# semantic_map_raw:
79+
# layers: ['elevation', 'traversability']
80+
# basic_layers: ['elevation', 'traversability']
81+
# fps: 5.0
82+
83+
#### Initializer ########
84+
initialize_method: 'linear' # Choose one from 'nearest', 'linear', 'cubic'
85+
initialize_frame_id: ['RF_FOOT', 'LF_FOOT', 'RH_FOOT', 'LH_FOOT'] # One tf (like ['footprint'] ) initializes a square around it.
86+
initialize_tf_offset: [0.0, 0.0, 0.0, 0.0] # z direction. Should be same number as initialize_frame_id.
87+
dilation_size_initialize: 5 # dilation size after the init.
88+
initialize_tf_grid_size: 0.4 # This is not used if number of tf is more than 3.
89+
use_initializer_at_start: true # Use initializer when the node starts.
Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
# Settings of the plugins. (The plugins should be stored in script/plugins)
2+
# min_filter fills in minimum value around the invalid cell.
3+
min_filter:
4+
enable: True # weather to load this plugin
5+
fill_nan: False # Fill nans to invalid cells of elevation layer.
6+
is_height_layer: True # If this is a height layer (such as elevation) or not (such as traversability)
7+
layer_name: "min_filter" # The layer name.
8+
extra_params: # This params are passed to the plugin class on initialization.
9+
dilation_size: 1 # The patch size to apply
10+
iteration_n: 30 # The number of iterations
11+
12+
max_filter:
13+
enable: True # weather to load this plugin
14+
fill_nan: False # Fill nans to invalid cells of elevation layer.
15+
is_height_layer: True # If this is a height layer (such as elevation) or not (such as traversability)
16+
layer_name: "max_filter" # The layer name.
17+
extra_params: # This params are passed to the plugin class on initialization.
18+
dilation_size: 5 # The patch size to apply
19+
iteration_n: 10 # The number of iterations
20+
21+
# Apply smoothing.
22+
smooth_filter:
23+
enable: True
24+
fill_nan: False
25+
is_height_layer: True
26+
layer_name: "smooth"
27+
extra_params:
28+
input_layer_name: "min_filter"
29+
30+
# Apply inpainting using opencv
31+
inpainting:
32+
enable: True
33+
fill_nan: False
34+
is_height_layer: True
35+
layer_name: "inpaint"
36+
extra_params:
37+
method: "telea" # telea or ns
Lines changed: 39 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,39 @@
1+
plugin_config_file: '$(rospack find elevation_mapping_cupy)/config/setups/g1/g1_plugin_config.yaml'
2+
3+
pointcloud_channel_fusions:
4+
rgb: 'color'
5+
default: 'average'
6+
7+
image_channel_fusions:
8+
rgb: 'color'
9+
default: 'exponential'
10+
feat_.*: 'exponential'
11+
sem_.*: 'exponential'
12+
13+
#### Publishers ########
14+
# topic_name:
15+
# layers: # Choose from 'elevation', 'variance', 'traversability', 'time', 'normal_x', 'normal_y', 'normal_z', 'color', plugin_layer_names
16+
# basic_layers: # basic_layers for valid cell computation (e.g. Rviz): Choose a subset of `layers`.
17+
# fps: # Publish rate. Use smaller value than `map_acquire_fps`.
18+
19+
publishers:
20+
elevation_map_raw:
21+
layers: ['elevation', 'traversability', 'variance', 'rgb', 'upper_bound']
22+
basic_layers: ['elevation', 'traversability']
23+
fps: 5.0
24+
25+
elevation_map_recordable:
26+
layers: ['elevation', 'traversability', 'variance', 'rgb']
27+
basic_layers: ['elevation', 'traversability']
28+
fps: 2.0
29+
30+
filtered_elevation_map:
31+
layers: ['inpaint', 'smooth', 'min_filter', 'max_filter', 'upper_bound']
32+
basic_layers: ['inpaint']
33+
fps: 5.0
34+
35+
#### Subscribers ########
36+
subscribers:
37+
Livox:
38+
topic_name: /cloud_registered_body_1
39+
data_type: pointcloud
Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
<launch>
2+
<!-- Elevation mapping node -->
3+
<node pkg="elevation_mapping_cupy" type="elevation_mapping_node" name="elevation_mapping" output="screen">
4+
<rosparam command="load" file="$(find elevation_mapping_cupy)/config/setups/g1/g1_parameters.yaml"/>
5+
<rosparam command="load" file="$(find elevation_mapping_cupy)/config/setups/g1/g1_sensor_parameter.yaml"/>
6+
</node>
7+
</launch>

0 commit comments

Comments
 (0)