diff --git a/config/dwa_base_local_planner_params.yaml b/config/dwa_base_local_planner_params.yaml index 0bc636a..88dab7e 100644 --- a/config/dwa_base_local_planner_params.yaml +++ b/config/dwa_base_local_planner_params.yaml @@ -1,4 +1,4 @@ -controller_frequency: 2.0 #20.0 #5.0 +controller_frequency: 3.0 #20.0 #5.0 recovery_behavior_enabled: true #false clearing_rotation_allowed: true #false @@ -9,7 +9,7 @@ DWAPlannerROS: min_vel_x: 0.1 #0.2 max_vel_y: 0.0 # zero for a differential drive robot min_vel_y: 0.0 - min_in_place_vel_theta: 0.5 + min_in_place_vel_theta: 0.1 #0.5 escape_vel: -0.1 acc_lim_x: 0.5 acc_lim_y: 0.0 # zero for a differential drive robot @@ -32,7 +32,7 @@ DWAPlannerROS: prune_plan: true # Forward Simulation Parameters - sim_time: 5.0 #1.0 #5.0 #2.5 + sim_time: 2.5 #5.0 #1.0 #5.0 #2.5 sim_granularity: 0.025 angular_sim_granularity: 0.025 vx_samples: 8 @@ -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: 0.5 # 0.01 - weighting for how much the controller should avoid obstacles + occdist_scale: 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