diff --git a/config/dwa_base_local_planner_params.yaml b/config/dwa_base_local_planner_params.yaml index 88dab7e..195b8ed 100644 --- a/config/dwa_base_local_planner_params.yaml +++ b/config/dwa_base_local_planner_params.yaml @@ -21,7 +21,7 @@ DWAPlannerROS: latch_xy_goal_tolerance: false pdist_scale: 0.8 gdist_scale: 0.6 - meter_scoring: true + #meter_scoring: true heading_lookahead: 0.325 heading_scoring: false @@ -44,7 +44,7 @@ DWAPlannerROS: # # Trajectory Scoring Parameters path_distance_bias: 64.0 # 32.0 - weighting for how much it should stick to the global path plan goal_distance_bias: 24.0 # 24.0 - wighting for how much it should attempt to reach its goal - occdist_scale: 2.0 #0.5 # 0.01 - weighting for how much the controller should avoid obstacles + occdist_scale: 10.0 #2.0 #0.5 # 0.01 - weighting for how much the controller should avoid obstacles forward_point_distance: 0.325 # 0.325 - how far along to place an additional scoring point stop_time_buffer: 0.2 # 0.2 - amount of time a robot must stop in before colliding for a valid traj. scaling_speed: 0.25 # 0.25 - absolute velocity at which to start scaling the robot's footprint