mirror of
https://github.com/bjoernellens1/cps_rmp220_support.git
synced 2024-11-23 15:45:08 +00:00
changed cost scaling factor
This commit is contained in:
parent
0608d4f2b5
commit
703d0be075
@ -211,7 +211,7 @@ local_costmap:
|
||||
enabled: True
|
||||
inflation_layer:
|
||||
plugin: "nav2_costmap_2d::InflationLayer"
|
||||
cost_scaling_factor: 15.0 # was 3.0
|
||||
cost_scaling_factor: 8.0 # was 3.0
|
||||
inflation_radius: 0.44
|
||||
voxel_layer:
|
||||
plugin: "nav2_costmap_2d::VoxelLayer"
|
||||
@ -273,7 +273,7 @@ global_costmap:
|
||||
map_subscribe_transient_local: True
|
||||
inflation_layer:
|
||||
plugin: "nav2_costmap_2d::InflationLayer"
|
||||
cost_scaling_factor: 15.0 # was 3.0
|
||||
cost_scaling_factor: 8.0 # was 3.0
|
||||
inflation_radius: 0.44
|
||||
always_send_full_costmap: True
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user