diff --git a/params/gmapping.yaml b/params/gmapping.yaml
index 8df1df357c839178768c8fa74f1ef7d993732214..a6f91b6961d007fcf3c817303558f01940805143 100644
--- a/params/gmapping.yaml
+++ b/params/gmapping.yaml
@@ -14,16 +14,16 @@ iterations: 5
 lsigma:     0.075
 ogain:      3.0
 lskip: 0
-minimumScore: 0.0 #0.0
+minimumScore: 50.0 #0.0
 srr: 0.1
 srt: 0.2
 str: 0.1
 stt: 0.2
-linearUpdate:      0.1 #1.0
-angularUpdate:     0.05 #0.5
+linearUpdate:      0.05 #1.0
+angularUpdate:     0.01 #0.5
 temporalUpdate:    1.0 #-1.0
 resampleThreshold: 0.5
-particles:         80 #30
+particles:         200 #30
 xmin: -5.0
 ymin: -5.0
 xmax:  5.0
diff --git a/params/local_planner/dwa_params.yaml b/params/local_planner/dwa_params.yaml
index 509483f1b699335fdafabad2e58f8288c1351091..56c9fb262b5eab39c0d2b6a9f12962d821d72ceb 100644
--- a/params/local_planner/dwa_params.yaml
+++ b/params/local_planner/dwa_params.yaml
@@ -18,7 +18,7 @@ DWAPlannerROS:
   #   are non-negligible and small in place rotational velocities will be created.
 
   max_vel_theta: 5.0  # choose slightly less than the base's capability
-  min_vel_theta: 0.4  # this is the min angular velocity when there is negligible translational velocity
+  min_vel_theta: 0.1  # this is the min angular velocity when there is negligible translational velocity
   theta_stopped_vel: 0.4
   
   acc_lim_x: 1.0 # maximum is theoretically 2.0, but we 
@@ -39,7 +39,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: 0.1            # 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