diff --git a/launch/include/move_base.launch b/launch/include/move_base.launch
index c6412b43fd9e585803563d9635f25411b69fac80..d2a73c83b4d5c2453102459d3be176ef102bc1cc 100644
--- a/launch/include/move_base.launch
+++ b/launch/include/move_base.launch
@@ -3,7 +3,7 @@
 <launch>
 
   <arg name="ns"             default="robot"/>
-  <arg name="path"           default="$(find iri_rosnav)"/>
+  <arg name="path"           default="$(find iri_rosnav)/params"/>
   <arg name="use_map"        default="true"/>
   <arg name="map_topic"      default="/$(arg ns)/map)"/>
   <arg name="odom_topic"     default="/$(arg ns)/odom"/>
@@ -26,15 +26,15 @@
       <remap from="cmd_vel" to="$(arg cmd_vel_topic)" />
       <remap from="odom"    to="$(arg odom_topic)" />
 
-      <rosparam file="$(arg path)/params/move_base_params.yaml"                            command="load" />
-      <rosparam file="$(arg path)/params/local_planner/$(arg local_planner)_params.yaml"   command="load" />
-      <rosparam file="$(arg path)/params/global_planner/$(arg global_planner)_params.yaml" command="load" />
+      <rosparam file="$(arg path)/move_base_params.yaml"                            command="load" />
+      <rosparam file="$(arg path)/local_planner/$(arg local_planner)_params.yaml"   command="load" />
+      <rosparam file="$(arg path)/global_planner/$(arg global_planner)_params.yaml" command="load" />
 
-      <rosparam file="$(arg path)/params/costmap/common_params.yaml" command="load" ns="local_costmap" />
-      <rosparam file="$(arg path)/params/costmap/local_params.yaml"  command="load" ns="local_costmap"/>
+      <rosparam file="$(arg path)/costmap/common_params.yaml" command="load" ns="local_costmap" />
+      <rosparam file="$(arg path)/costmap/local_params.yaml"  command="load" ns="local_costmap"/>
 
-      <rosparam file="$(arg path)/params/costmap/common_params.yaml"                     command="load" ns="global_costmap" />
-      <rosparam file="$(arg path)/params/costmap/$(arg costmap_path)/global_params.yaml" command="load" ns="global_costmap"/> 
+      <rosparam file="$(arg path)/costmap/common_params.yaml"                     command="load" ns="global_costmap" />
+      <rosparam file="$(arg path)/costmap/$(arg costmap_path)/global_params.yaml" command="load" ns="global_costmap"/> 
 
     </node>
 
diff --git a/launch/nav.launch b/launch/nav.launch
index 61c02847ba1decee98b7be59be5107ca53a65cd3..918e07f29b413797af40bcf9379aee77d5956b2e 100644
--- a/launch/nav.launch
+++ b/launch/nav.launch
@@ -2,7 +2,9 @@
 <!-- -->
 <launch>
   <arg name="ns"             default="robot"/>
-  <arg name="path"           default="$(find iri_rosnav)"/>
+  <arg name="pkg"            default="iri_rosnav"/>
+    <arg name="path"         default="$(eval find(arg('pkg')))"/>
+  <arg name="param_subpath" default="params"/>
   <arg name="map_frame_id"   default="map"/>
   <arg name="odom_frame_id"  default="$(arg ns)/odom"/>
   <arg name="base_frame_id"  default="$(arg ns)/base_footprint"/>
@@ -10,23 +12,23 @@
   <arg name="map_service"    default="/$(arg ns)/static_map"/>
   <arg name="odom_topic"     default="/$(arg ns)/odom"/>
   <arg name="cmd_vel_topic"  default="/$(arg ns)/navigation/cmd_vel"/>
-  <arg name="scan_topic"     default="/$(arg ns)/scan"/>
+  <arg name="scan_topic"     default="/$(arg ns)/sensors/scan"/>
   <arg name="use_map"        default="true"/>
   <arg name="use_map_server" default="true"/>
     <arg name="map_name"       default="willow"/>
   <arg name="use_amcl"       default="true"/>
-    <arg name="amcl_config"    default="$(arg path)/params/amcl.yaml"/>
+    <arg name="amcl_config"    default="$(arg path)/$(arg param_subpath)/amcl.yaml"/>
     <arg name="initial_x"      default="0.0"/>
     <arg name="initial_y"      default="0.0"/>
     <arg name="initial_yaw"    default="0.0"/>
   <arg name="use_fake_loc"   default="false"/>
   <arg name="use_gmapping"   default="false"/>
     <arg name="gmapping_scan_topic"     default="/$(arg ns)/front_hokuyo_scan"/>
-    <arg name="gmapping_config" default="$(arg path)/params/gmapping.yaml"/>
+    <arg name="gmapping_config" default="$(arg path)/$(arg param_subpath)/gmapping.yaml"/>
     <arg name="resolution"     default="0.1"/>
   <arg name="use_cmd_vel_mux"      default="false"/>
     <arg name="nodelet_manager_name" default="nodelet_manager"/>
-    <arg name="cmd_vel_mux_config"   default="$(arg path)/params/mux.yaml"/>
+    <arg name="cmd_vel_mux_config"   default="$(arg path)/$(arg param_subpath)/mux.yaml"/>
   <arg name="use_move_base"  default="true"/>
     <arg name="local_planner"  default="dwa"/>
     <arg name="global_planner" default="global_planner"/>
@@ -78,16 +80,14 @@
       </include>
     </group>
   </group>
-  
-  <group unless="$(arg use_map)">
 
+  <group unless="$(arg use_map)">
     <node pkg="tf" 
           type="static_transform_publisher" 
           name="static_tf_map"
           ns="$(arg ns)"
           args=" 0 0 0 0 0 0 $(arg map_frame_id) $(arg odom_frame_id) 100">
     </node>
-    
   </group>
 
   <group if="$(arg use_fake_loc)"> 
@@ -119,7 +119,7 @@
   <group if="$(arg use_move_base)"> 
     <include file="$(find iri_rosnav)/launch/include/move_base.launch">
       <arg name="ns"             value="$(arg ns)"/>
-      <arg name="path"           value="$(arg path)"/>
+      <arg name="path"           value="$(arg path)/$(arg param_subpath)"/>
       <arg name="use_map"        value="$(arg use_map_server)"/> 
       <arg name="map_topic"      value="$(arg map_topic)"/>
       <arg name="odom_topic"     value="$(arg odom_topic)"/>
diff --git a/params/amcl.yaml b/params/amcl.yaml
index 7049474c11b95251ef462ecf0bd5645a406d4dfc..15ab9b160b244e108d955e242fb3af0d45b13dde 100644
--- a/params/amcl.yaml
+++ b/params/amcl.yaml
@@ -36,10 +36,10 @@ laser_lambda_short: 0.1
 laser_likelihood_max_dist: 2.0
 laser_model_type: 'likelihood_field'
 # odom parameters
-odom_model_type: "diff"
-odom_alpha1: 0.2
-odom_alpha2: 0.2
-odom_alpha3: 0.2
-odom_alpha4: 0.2
-odom_alpha5: 0.2
+odom_model_type: "diff-corrected"
+odom_alpha1: 0.005
+odom_alpha2: 0.005
+odom_alpha3: 0.01
+odom_alpha4: 0.005
+odom_alpha5: 0.003
 tf_broadcast: true
diff --git a/params/local_planner/dwa_params.yaml b/params/local_planner/dwa_params.yaml
index 38a3b40d27657a0ad2e3ed491db4ba60c90969d2..2d58b071e7927184681f14fa43f91e51e0691e52 100644
--- a/params/local_planner/dwa_params.yaml
+++ b/params/local_planner/dwa_params.yaml
@@ -50,5 +50,5 @@ DWAPlannerROS:
 
   #not in dynamic reconfigure
   publish_traj_pc: false
-  #global_frame_id: /robot/base_footprint
+  #global_frame_id: /robot/odom
   publish_cost_grid_pc: false