From c3dc9fefbba4a388c2873627521c399e826d4034 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bj=C3=B6rn=20Ellensohn?= Date: Mon, 21 Aug 2023 10:03:22 +0200 Subject: [PATCH] update footprint in global costmap --- config/nav2_params.yaml | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/config/nav2_params.yaml b/config/nav2_params.yaml index 20cda41..62d2915 100644 --- a/config/nav2_params.yaml +++ b/config/nav2_params.yaml @@ -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