From e8230ee2c5fdd15175bce8ba99df2b686b56306d Mon Sep 17 00:00:00 2001 From: Erik Andresen Date: Mon, 5 Jun 2017 11:10:07 +0200 Subject: [PATCH] Adapt navigation config to more trustworthy IMU --- config/base_local_planner_params.yaml | 6 +++--- config/global_costmap_params.yaml | 4 +++- launch/move_base.launch | 4 ++-- 3 files changed, 8 insertions(+), 6 deletions(-) diff --git a/config/base_local_planner_params.yaml b/config/base_local_planner_params.yaml index 1823408..ce83faa 100644 --- a/config/base_local_planner_params.yaml +++ b/config/base_local_planner_params.yaml @@ -14,14 +14,14 @@ TrajectoryPlannerROS: # gdist_scale and pdist_scale parameters should assume meters meter_scoring: true - xy_goal_tolerance: 0.20 - yaw_goal_tolerance: 0.3 + xy_goal_tolerance: 0.15 + yaw_goal_tolerance: 0.1 # The weighting for how much the controller should attempt to avoid obstacles, default: 0.01 occdist_scale: 0.02 # Whether to score based on the robot's heading to the path or its distance from the path, default: false - heading_scoring: true + heading_scoring: false # How far to look ahead in time in seconds along the simulated trajectory when using heading scoring, default: 0.1 heading_scoring_timestep: 0.3 diff --git a/config/global_costmap_params.yaml b/config/global_costmap_params.yaml index dde44ae..3dfcf59 100644 --- a/config/global_costmap_params.yaml +++ b/config/global_costmap_params.yaml @@ -8,4 +8,6 @@ global_costmap: - {name: inflation_layer, type: 'costmap_2d::InflationLayer'} inflation_layer: - inflation_radius: 0.25 + # low slope decay curve + inflation_radius: 1.75 + cost_scaling_factor: 2.58 diff --git a/launch/move_base.launch b/launch/move_base.launch index f2fd733..9c6755d 100644 --- a/launch/move_base.launch +++ b/launch/move_base.launch @@ -25,9 +25,9 @@ - + - + -- 2.39.2