Skip to content

Commit

Permalink
tune costmap parameters (#15)
Browse files Browse the repository at this point in the history
* tune costmap parameters:
- increase local costmap size
- use transient local, so that map can be fetched directly after restart
- do not send the full costmap, to reduce bandwith consumption

* Change publish and update frequencies

* Update forklift_params.yaml

Co-authored-by: rdeniza <61455514+rdeniza@users.noreply.github.com>
  • Loading branch information
jplapp and rdeniza committed Dec 28, 2020
1 parent eb880c5 commit a25fd33
Showing 1 changed file with 8 additions and 8 deletions.
16 changes: 8 additions & 8 deletions nav2_bringup/bringup/params/forklift_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -72,23 +72,23 @@ local_costmap:
local_costmap:
ros__parameters:
global_frame: odom
update_frequency: 2.0
publish_frequency: 2.0
update_frequency: 5.0
publish_frequency: 1.0
robot_base_frame: base_link
map_topic: /costmap_node/map
plugins: ["static_layer", "obstacle_layer"]
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: False
map_subscribe_transient_local: True
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: false
rolling_window: True
width: 7
height: 7
width: 15
height: 15
resolution: 0.1
footprint: "[[1.8, 0.4], [1.8, -0.4], [-0.2, -0.4], [-0.2, 0.4]]"
always_send_full_costmap: True
always_send_full_costmap: False
local_costmap_client:
ros__parameters:
use_sim_time: True
Expand Down Expand Up @@ -222,12 +222,12 @@ global_costmap:
observation_sources: scan
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: False
map_subscribe_transient_local: True
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 10.0
inflation_radius: 0.55
always_send_full_costmap: True
always_send_full_costmap: False
global_costmap_client:
ros__parameters:
use_sim_time: True
Expand Down

0 comments on commit a25fd33

Please sign in to comment.