diff --git a/launch/include/localization.launch b/launch/include/localization.launch
index 1809f0f36e38c2f7ba6c75eec1a88cdde9ab7238..2c1407eebe8563124ee1be4dc1d2f7a12296214c 100644
--- a/launch/include/localization.launch
+++ b/launch/include/localization.launch
@@ -3,13 +3,13 @@
 <launch>
 
   <arg name="name" default="model_car"/>
-  <arg name="local_ekf_yaml_filename" default="local_ekf_odom_imu"/>
-  <arg name="global_ekf_yaml_filename" default="global_ekf_odom_imu"/>
+  <arg name="local_ekf_yaml_file"  default="$(find iri_model_car_rosnav)/params/$(arg name)_local_ekf.yaml"/>
+  <arg name="global_ekf_yaml_file" default="$(find iri_model_car_rosnav)/params/$(arg name)_global_ekf.yaml"/>
   <arg name="global_loc" default="false"/>
 
   <node pkg="imu_msg_fix" 
         name="imu_msg_fix"
-	ns="$(arg name)"
+        ns="$(arg name)"
         type="imu_msg_fix" 
         output="screen">
     <param name="fix_frame_id"       value="false"/>
@@ -18,7 +18,7 @@
     <param name="cov_orientation"    value="0.01"/>
     <param name="cov_vel"            value="0.01"/>
     <param name="cov_acc"            value="0.01"/>
-    <param name="imu_reference"      value="1"/><!-- 0 -> NED 1-> ENU -->
+    <param name="imu_reference"      value="1"/><!-- 0->NED, 1->ENU -->
     <remap from="~imu_in" to="sensors/imu"/>
     <remap from="~imu_out" to="sensors/imu_enu"/>
 
@@ -28,10 +28,10 @@
   <node pkg="robot_localization" 
         type="ekf_localization_node" 
         name="local_ekf"
-	ns="$(arg name)"
+        ns="$(arg name)"
         clear_params="true"
         output="screen">
-    <rosparam command="load" file="$(find iri_model_car_rosnav)/params/$(arg local_ekf_yaml_filename).yaml" />
+    <rosparam command="load" file="$(arg local_ekf_yaml_file)" />
     <remap from="odometry/filtered" to="/$(arg name)/local_odom_combined"/>
   </node>
 
@@ -40,20 +40,20 @@
         type="static_transform_publisher" 
         name="map_transform" args="0 0 0 0 0 0 map model_car/odom 20"
         unless="$(arg global_loc)"/> 
--->
+  -->
 
   <node pkg="robot_localization" 
         type="ekf_localization_node" 
         name="global_ekf"
-	ns="$(arg name)"
+        ns="$(arg name)"
         clear_params="true"
         output="screen"
         if="$(arg global_loc)"> 
-    <rosparam command="load" file="$(find iri_model_car_rosnav)/params/$(arg global_ekf_yaml_filename).yaml" />
+    <rosparam command="load" file="$(arg global_ekf_yaml_file)" />
     <remap from="odometry/filtered" to="/$(arg name)/global_odom_combined"/>
   </node>
 
-<!--
+  <!--
   <node pkg="robot_localization" 
         type="navsat_transform_node" 
         name="navsat_transform_node"
@@ -75,7 +75,7 @@
     <remap from="/odometry/filtered"           to="/$(arg name)/global_odom_combined" />
     <remap from="/odometry/gps"                to="/$(arg name)/gps_odometry" />
   </node>
--->
+  -->
 
   <!--
   <node pkg="robot_localization" 
@@ -104,4 +104,3 @@
   -->
 
 </launch>
-
diff --git a/launch/nav_map.launch b/launch/nav_map.launch
index 1aa2439890f2e6ab44e0dff5ad44f9524c64604b..bf13f468a506f02561c06890d7b7471f32369900 100644
--- a/launch/nav_map.launch
+++ b/launch/nav_map.launch
@@ -3,6 +3,7 @@
 <launch>
 
   <arg name="name"                    default="model_car"/>
+  <arg name="params_path"             default="$(find iri_model_car_rosnav)/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"/>
@@ -13,6 +14,7 @@
   <arg name="cmd_vel_topic"           default="/$(arg name)/navigation/cmd_vel"/>
   <arg name="map_path"                default="$(find iri_maps)/map"/>
   <arg name="map_name"                default="empty" />
+  <arg name="amcl_config"             default="$(find iri_model_car_rosnav)/params/amcl_no_tf.yaml"/>
   <arg name="initial_x"               default="0.0"/>
   <arg name="initial_y"               default="0.0"/>
   <arg name="initial_yaw"             default="0.0"/>
@@ -24,7 +26,7 @@
 
   <include file="$(find iri_rosnav)/launch/nav.launch">
     <arg name="ns"                      value="$(arg name)"/>
-    <arg name="path"                    value="$(find iri_model_car_rosnav)/params"/>
+    <arg name="path"                    value="$(arg params_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)"/>
@@ -42,7 +44,7 @@
     <arg name="map_path"                value="$(arg map_path)"/>
     <arg name="map_name"                value="$(arg map_name)"/>
     <arg name="use_amcl"                value="true"/>
-    <arg name="amcl_config"             value="$(find iri_model_car_rosnav)/params/amcl_no_tf.yaml"/>
+    <arg name="amcl_config"             value="$(arg amcl_config)"/>
     <arg name="initial_x"               value="$(arg initial_x)"/>
     <arg name="initial_y"               value="$(arg initial_y)"/>
     <arg name="initial_yaw"             value="$(arg initial_yaw)"/>