update footprint in global costmap

This commit is contained in:
Björn Ellensohn 2023-08-21 10:03:22 +02:00
parent 5267a521d5
commit c3dc9fefbb

View File

@ -211,7 +211,7 @@ local_costmap:
enabled: True
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 10.0 # was 3.0
cost_scaling_factor: 15.0 # was 3.0
inflation_radius: 0.22
voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
@ -246,7 +246,8 @@ global_costmap:
global_frame: map
robot_base_frame: base_link
use_sim_time: True
robot_radius: 0.50
#robot_radius: 0.50
footprint: "[ [0.21, 0.255], [0.21, -0.255], [-0.52, -0.255], [-0.52, 0.255] ]"
resolution: 0.05
track_unknown_space: true
plugins: ["static_layer", "obstacle_layer", "inflation_layer", "denoise_layer"]
@ -272,7 +273,7 @@ global_costmap:
map_subscribe_transient_local: True
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 10.0 # was 3.0
cost_scaling_factor: 15.0 # was 3.0
inflation_radius: 0.22
always_send_full_costmap: True