mirror of
https://github.com/bjoernellens1/cps_rmp220_support.git
synced 2024-11-23 15:45:08 +00:00
update
This commit is contained in:
parent
944fb79401
commit
92067d1c19
@ -546,44 +546,44 @@ global_costmap:
|
||||
footprint: "[ [0.18, 0.255], [0.18, -0.255], [-0.54, -0.165], [-0.54, 0.165] ]" # gave another points for the polygon
|
||||
resolution: 0.05
|
||||
track_unknown_space: true
|
||||
plugins: ["static_layer", "inflation_layer", "denoise_layer", "stvl_layer"] # remove "obstacle_layer",
|
||||
stvl_layer:
|
||||
plugin: "spatio_temporal_voxel_layer/SpatioTemporalVoxelLayer"
|
||||
enabled: true
|
||||
voxel_decay: 15.
|
||||
decay_model: 0
|
||||
voxel_size: 0.05
|
||||
track_unknown_space: true
|
||||
unknown_threshold: 15
|
||||
mark_threshold: 0
|
||||
update_footprint_enabled: true
|
||||
combination_method: 1
|
||||
origin_z: 0.0
|
||||
publish_voxel_map: true
|
||||
transform_tolerance: 0.2
|
||||
mapping_mode: false
|
||||
map_save_duration: 60.0
|
||||
observation_sources: pointcloud
|
||||
pointcloud:
|
||||
data_type: PointCloud2
|
||||
topic: /stereo/points
|
||||
marking: true
|
||||
clearing: true
|
||||
obstacle_range: 1.0 # was 3.0
|
||||
min_obstacle_height: 0.0
|
||||
max_obstacle_height: 2.0
|
||||
expected_update_rate: 0.0
|
||||
observation_persistence: 0.0
|
||||
inf_is_valid: false
|
||||
filter: "voxel"
|
||||
voxel_min_points: 0
|
||||
clear_after_reading: true
|
||||
max_z: 7.0
|
||||
min_z: 0.1
|
||||
vertical_fov_angle: 0.8745
|
||||
horizontal_fov_angle: 1.048
|
||||
decay_acceleration: 15.0
|
||||
model_type: 0
|
||||
plugins: ["static_layer", "inflation_layer", "denoise_layer"] # remove "obstacle_layer", , "stvl_layer"
|
||||
# stvl_layer:
|
||||
# plugin: "spatio_temporal_voxel_layer/SpatioTemporalVoxelLayer"
|
||||
# enabled: true
|
||||
# voxel_decay: 15.
|
||||
# decay_model: 0
|
||||
# voxel_size: 0.05
|
||||
# track_unknown_space: true
|
||||
# unknown_threshold: 15
|
||||
# mark_threshold: 0
|
||||
# update_footprint_enabled: true
|
||||
# combination_method: 1
|
||||
# origin_z: 0.0
|
||||
# publish_voxel_map: true
|
||||
# transform_tolerance: 0.2
|
||||
# mapping_mode: false
|
||||
# map_save_duration: 60.0
|
||||
# observation_sources: pointcloud
|
||||
# pointcloud:
|
||||
# data_type: PointCloud2
|
||||
# topic: /stereo/points
|
||||
# marking: true
|
||||
# clearing: true
|
||||
# obstacle_range: 1.0 # was 3.0
|
||||
# min_obstacle_height: 0.0
|
||||
# max_obstacle_height: 2.0
|
||||
# expected_update_rate: 0.0
|
||||
# observation_persistence: 0.0
|
||||
# inf_is_valid: false
|
||||
# filter: "voxel"
|
||||
# voxel_min_points: 0
|
||||
# clear_after_reading: true
|
||||
# max_z: 7.0
|
||||
# min_z: 0.1
|
||||
# vertical_fov_angle: 0.8745
|
||||
# horizontal_fov_angle: 1.048
|
||||
# decay_acceleration: 15.0
|
||||
# model_type: 0
|
||||
denoise_layer:
|
||||
plugin: "nav2_costmap_2d::DenoiseLayer"
|
||||
enabled: True
|
||||
|
Loading…
Reference in New Issue
Block a user