Skip to content
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
44 changes: 13 additions & 31 deletions go2_robot_sdk/config/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -181,36 +181,32 @@ controller_server:
local_costmap:
local_costmap:
ros__parameters:
update_frequency: 1.0
publish_frequency: 1.0
update_frequency: 2.0
publish_frequency: 2.0
global_frame: odom
robot_base_frame: base_link
use_sim_time: False
rolling_window: true
width: 6
height: 6
always_send_full_costmap: true
width: 8
height: 8
resolution: 0.05
footprint: "[ [0.360, 0.200], [0.360, -0.200], [-0.450, -0.200], [-0.450, 0.200] ]"
plugins: ["static_layer", "voxel_layer", "inflation_layer"]
plugins: ["obstacle_layer", "inflation_layer"]

static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True

voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True
publish_voxel_map: True
observation_sources: scan
scan:
topic: /scan
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "LaserScan"
raytrace_max_range: 3.0
raytrace_max_range: 6.0
raytrace_min_range: 0.0
obstacle_max_range: 2.5
obstacle_max_range: 5.5
obstacle_min_range: 0.0

inflation_layer:
Expand All @@ -221,7 +217,7 @@ local_costmap:
global_costmap:
global_costmap:
ros__parameters:
update_frequency: 1.0
update_frequency: 0.0 # Set to 0 to prevent dynamic updates
publish_frequency: 1.0
global_frame: odom
robot_base_frame: base_link
Expand All @@ -234,27 +230,13 @@ global_costmap:
origin_x: -250.0
origin_y: -250.0
footprint: "[ [0.360, 0.200], [0.360, -0.200], [-0.450, -0.200], [-0.450, 0.200] ]"
plugins: ["static_layer", "voxel_layer", "inflation_layer"]
plugins: ["static_layer", "inflation_layer"] # Removed voxel_layer

static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True

voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
enabled: True
publish_voxel_map: True
observation_sources: scan
scan:
topic: scan
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "LaserScan"
raytrace_max_range: 3.0
raytrace_min_range: 0.0
obstacle_max_range: 2.5
obstacle_min_range: 0.0
subscribe_to_updates: False # Don't subscribe to map updates

inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
Expand Down