Skip to content

Commit

Permalink
Merge pull request #11 from logivations/task_wmo_56527_use_same_footp…
Browse files Browse the repository at this point in the history
…rint_for_global_and_local_planner_adapt_inflation_layers_smac

WMO-56527 Use same footprint for global and local planner: Adapt Inflation layers, SMAC
  • Loading branch information
rdeniza authored Dec 16, 2020
2 parents 63a1c19 + c12cb72 commit 931c649
Showing 1 changed file with 21 additions and 12 deletions.
33 changes: 21 additions & 12 deletions nav2_bringup/bringup/params/forklift_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,11 @@ controller_server:
no_outer_iterations: 4
max_number_classes: 4
min_turning_radius: 0.2
use_sin_cos_approximation: True
weight_velocity_obstacle_ratio: 10.0
obstacle_proximity_ratio_max_vel: 0.8
obstacle_proximity_lower_bound: 0.0
obstacle_proximity_upper_bound: 1.0


controller_server_rclcpp_node:
Expand All @@ -62,20 +67,20 @@ controller_server_rclcpp_node:
local_costmap:
local_costmap:
ros__parameters:
global_frame: map
global_frame: odom
update_frequency: 10.0
publish_frequency: 7.0
robot_base_frame: base_link
plugins: ["obstacle_layer"]
obstacle_layer.plugin: "nav2_costmap_2d::ObstacleLayer"
map_topic: /costmap_node/map
plugins: ["static_layer"]
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: False
rolling_window: True
width: 8
height: 8
width: 7
height: 7
resolution: 2.0
robot_radius: 0.25
obstacle_layer:
enabled: True
observation_sources: scan
static_layer:
map_subscribe_transient_local: True
footprint: "[[1.8, 0.4], [1.8, -0.4], [-0.2, -0.4], [-0.2, 0.4]]"
always_send_full_costmap: True
local_costmap_client:
ros__parameters:
Expand Down Expand Up @@ -203,14 +208,18 @@ global_costmap:
footprint: "[[1.8, 0.4], [1.8, -0.4], [-0.2, -0.4], [-0.2, 0.4]]"
map_topic: /costmap_node/map
track_unknown_space: false
plugins: ["static_layer", "obstacle_layer"]
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: false
observation_sources: scan
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: False
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 10.0
inflation_radius: 0.55
always_send_full_costmap: True
global_costmap_client:
ros__parameters:
Expand Down

0 comments on commit 931c649

Please sign in to comment.