This commit is contained in:
Björn Ellensohn 2023-10-02 09:50:03 +02:00
parent 577e195aa7
commit 7e912cc8be

View File

@ -546,7 +546,7 @@ 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 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 resolution: 0.05
track_unknown_space: true track_unknown_space: true
plugins: ["static_layer", "obstacle_layer", "inflation_layer", "denoise_layer", "stvl_layer"] plugins: ["static_layer", "inflation_layer", "denoise_layer", "stvl_layer"] # remove "obstacle_layer",
stvl_layer: stvl_layer:
plugin: "spatio_temporal_voxel_layer/SpatioTemporalVoxelLayer" plugin: "spatio_temporal_voxel_layer/SpatioTemporalVoxelLayer"
enabled: true enabled: true
@ -587,20 +587,20 @@ global_costmap:
denoise_layer: denoise_layer:
plugin: "nav2_costmap_2d::DenoiseLayer" plugin: "nav2_costmap_2d::DenoiseLayer"
enabled: True enabled: True
obstacle_layer: # obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer" # plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True # enabled: True
observation_sources: scan # observation_sources: scan
scan: # scan:
topic: /scan # topic: /scan
max_obstacle_height: 2.0 # max_obstacle_height: 2.0
clearing: True # clearing: True
marking: True # marking: True
data_type: "LaserScan" # data_type: "LaserScan"
raytrace_max_range: 8.0 # was 3.0 # raytrace_max_range: 8.0 # was 3.0
raytrace_min_range: 0.0 # raytrace_min_range: 0.0
obstacle_max_range: 2.5 # obstacle_max_range: 2.5
obstacle_min_range: 0.0 # obstacle_min_range: 0.0
static_layer: static_layer:
plugin: "nav2_costmap_2d::StaticLayer" plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True map_subscribe_transient_local: True