From f1096738b1cb44e0abdb7e85ddd66cc44a48323a Mon Sep 17 00:00:00 2001 From: Erik Andresen Date: Sat, 8 Jul 2017 17:51:44 +0200 Subject: [PATCH 1/1] Move config/global_costmap_params_odom.yaml go config/global_costmap_params_utm.yaml --- config/base_local_planner_params.yaml | 3 +++ config/global_costmap_params.yaml | 8 ++++---- ...p_params_odom.yaml => global_costmap_params_utm.yaml} | 9 ++++----- launch/move_base.launch | 8 +++++--- 4 files changed, 16 insertions(+), 12 deletions(-) rename config/{global_costmap_params_odom.yaml => global_costmap_params_utm.yaml} (72%) diff --git a/config/base_local_planner_params.yaml b/config/base_local_planner_params.yaml index ce83faa..b163e5e 100644 --- a/config/base_local_planner_params.yaml +++ b/config/base_local_planner_params.yaml @@ -26,6 +26,9 @@ TrajectoryPlannerROS: # 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 + # How far the robot must travel in meters before oscillation flags are reset, default: 0.05 + oscillation_reset_dist: 0.1 + DWAPlannerROS: acc_lim_x: 10.07 acc_lim_y: 0.0 diff --git a/config/global_costmap_params.yaml b/config/global_costmap_params.yaml index 3dfcf59..5bb308d 100644 --- a/config/global_costmap_params.yaml +++ b/config/global_costmap_params.yaml @@ -7,7 +7,7 @@ global_costmap: - {name: static_layer, type: 'costmap_2d::StaticLayer'} - {name: inflation_layer, type: 'costmap_2d::InflationLayer'} -inflation_layer: - # low slope decay curve - inflation_radius: 1.75 - cost_scaling_factor: 2.58 + inflation_layer: + # low slope decay curve + inflation_radius: 1.75 + cost_scaling_factor: 2.58 diff --git a/config/global_costmap_params_odom.yaml b/config/global_costmap_params_utm.yaml similarity index 72% rename from config/global_costmap_params_odom.yaml rename to config/global_costmap_params_utm.yaml index 0cb31e5..8ecf0b5 100644 --- a/config/global_costmap_params_odom.yaml +++ b/config/global_costmap_params_utm.yaml @@ -1,11 +1,10 @@ # only differences to config/global_costmap_params.yaml global_costmap: - global_frame: odom + global_frame: utm rolling_window: true - width: 100.0 - height: 100.0 - resolution: 1.0 - resolution: 0.05 + width: 200.0 + height: 200.0 + resolution: 0.10 plugins: - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'} - {name: inflation_layer, type: 'costmap_2d::InflationLayer'} diff --git a/launch/move_base.launch b/launch/move_base.launch index c1320cb..9508c32 100644 --- a/launch/move_base.launch +++ b/launch/move_base.launch @@ -2,6 +2,7 @@ + @@ -19,9 +20,9 @@ - + - + @@ -41,7 +42,8 @@ - + + -- 2.39.2