diff --git a/config/nav2_params.yaml b/config/nav2_params.yaml index 1ba776b..b8da8ff 100644 --- a/config/nav2_params.yaml +++ b/config/nav2_params.yaml @@ -191,7 +191,8 @@ local_costmap: width: 3 height: 3 resolution: 0.05 - robot_radius: 0.22 + #robot_radius: 0.22 + footprint: "[ [0.18, 0.255], [0.18, -0.255], [-0.54, -0.165], [-0.54, 0.165] ]" # gave another points for the polygon plugins: ["voxel_layer", "inflation_layer"] inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" @@ -230,7 +231,8 @@ global_costmap: global_frame: map robot_base_frame: base_link use_sim_time: True - robot_radius: 0.22 + #robot_radius: 0.22 + 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", "obstacle_layer", "inflation_layer"]