diff --git a/launch/nav_mapping.launch b/launch/nav_mapping.launch
new file mode 100644
index 0000000000000000000000000000000000000000..e231bd5b6318fec5737e1bcede37d7ed01d6c89a
--- /dev/null
+++ b/launch/nav_mapping.launch
@@ -0,0 +1,56 @@
+<?xml version="1.0"?>
+<!-- -->
+<launch>
+  <arg name="name"                    default="turtlebot"/>
+  <arg name="path"                    default="$(find iri_turtlebot_launch)/params"/>
+  <arg name="move_base_params"        default="move_base_params.yaml"/>
+  <arg name="costmap_common_params"   default="common_params.yaml"/>
+  <arg name="costmap_local_params"    default="local_params.yaml"/>
+  <arg name="costmap_global_params"   default="global_params.yaml"/>
+  <arg name="map_frame_id"            default="map"/>
+  <arg name="resolution"              default="0.1"/>
+  <arg name="local_planner"           default="dwa"/>
+  <arg name="global_planner"          default="global_planner"/>
+  <arg name="rviz"                    default="true"/>
+  <arg name="rviz_file"               default="$(find iri_turtlebot_launch)/rviz/nav.rviz"/>
+  <arg name="output"                  default="screen" />
+  <arg name="launch_prefix"           default="" />
+
+  <include file="$(find iri_rosnav)/launch/nav.launch">
+    <arg name="ns"                    value="$(arg name)"/>
+    <arg name="path"                  value="$(arg path)"/>
+    <arg name="move_base_params"      value="$(arg move_base_params)"/>
+    <arg name="costmap_common_params" value="$(arg costmap_common_params)"/>
+    <arg name="costmap_local_params"  value="$(arg costmap_local_params)"/>
+    <arg name="costmap_global_params" value="$(arg costmap_global_params)"/>
+    <arg name="map_frame_id"          value="map"/>
+    <arg name="odom_frame_id"         value="odom"/>
+    <arg name="base_frame_id"         value="base_footprint"/>
+    <arg name="map_topic"             value="/$(arg name)/map"/>
+    <arg name="map_service"           value="/$(arg name)/static_map"/>
+    <arg name="odom_topic"            value="/odom"/>
+    <arg name="cmd_vel_topic"         value="/cmd_vel_mux/input/navi"/>
+    <arg name="scan_topic"            value="/scan"/>
+    <arg name="use_map"               value="true"/>
+    <arg name="use_map_server"        value="false"/> 
+    <arg name="map_name"              value="empty"/>
+    <arg name="use_amcl"              value="false"/>
+    <arg name="use_fake_loc"          value="false"/>
+    <arg name="use_gmapping"          value="true"/>
+    <arg name="gmapping_scan_topic"   value="/scan"/>
+    <arg name="gmapping_config"       value="$(find iri_turtlebot_launch)/params/gmapping.yaml"/>
+    <arg name="resolution"            value="$(arg resolution)"/>
+    <arg name="local_planner"         value="$(arg local_planner)"/>
+    <arg name="global_planner"        value="$(arg global_planner)"/>
+    <arg name="output"                value="$(arg output)" />
+    <arg name="launch_prefix"         value="$(arg launch_prefix)" />
+  </include>
+
+  <node name="rviz"
+        pkg="rviz"
+        type="rviz"
+        if="$(arg rviz)"
+        args="-d $(arg rviz_file)">
+  </node>
+
+</launch>
diff --git a/params/costmap/common_params.yaml b/params/costmap/common_params.yaml
index fb961cc73f2411d9cbbfd67a8f039e302f942d5d..d132f55bfd98956b25acabe58d4aa7bf15baf20b 100644
--- a/params/costmap/common_params.yaml
+++ b/params/costmap/common_params.yaml
@@ -32,14 +32,14 @@ obstacle_layer:
   observation_sources:  scan bump
   scan:
     data_type: LaserScan
-    topic: scan
+    topic: /scan
     marking: true
     clearing: true
     min_obstacle_height: 0.25
     max_obstacle_height: 0.35
   bump:
     data_type: PointCloud2
-    topic: mobile_base/sensors/bumper_pointcloud
+    topic: /mobile_base/sensors/bumper_pointcloud
     marking: true
     clearing: false
     min_obstacle_height: 0.0
diff --git a/params/gmapping.yaml b/params/gmapping.yaml
index d7c5f34befbeeeabcd17b68ef8a1cae8d1141d43..a6f91b6961d007fcf3c817303558f01940805143 100644
--- a/params/gmapping.yaml
+++ b/params/gmapping.yaml
@@ -1,5 +1,11 @@
-map_update_interval: 5.0
-maxUrange: 29.0
+#name: value #default_value
+
+throttle_scans: 1
+#base_frame: base_link
+#map_frame: map
+#odom_frame: odom
+map_update_interval: 1.0 #5.0
+maxUrange: 7.8 #80.0
 sigma:      0.05
 kernelSize: 1
 lstep:      0.05
@@ -8,23 +14,25 @@ iterations: 5
 lsigma:     0.075
 ogain:      3.0
 lskip: 0
+minimumScore: 50.0 #0.0
 srr: 0.1
 srt: 0.2
 str: 0.1
 stt: 0.2
-linearUpdate:      0.5
-angularUpdate:     0.5
-temporalUpdate:    10.0
+linearUpdate:      0.05 #1.0
+angularUpdate:     0.01 #0.5
+temporalUpdate:    1.0 #-1.0
 resampleThreshold: 0.5
-particles:         80
-
+particles:         200 #30
 xmin: -5.0
 ymin: -5.0
 xmax:  5.0
 ymax:  5.0
-
-delta: 0.1
+delta: 0.05 #0.05
 llsamplerange: 0.01
 llsamplestep:  0.01
 lasamplerange: 0.005
-lasamplestep:  0.005
\ No newline at end of file
+lasamplestep:  0.005
+transform_publish_period: 0.05
+occ_thresh: 0.25
+maxRange: 8.5
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