diff --git a/launch/include/map_server.launch b/launch/include/map_server.launch
index 1ec5a418e0d1ea68c931ef45441688fa7a09170a..d1530600fe4d648623cbd14f2281b2e911589882 100644
--- a/launch/include/map_server.launch
+++ b/launch/include/map_server.launch
@@ -3,6 +3,7 @@
 <launch>
 
   <arg name="ns"           default="robot"/>
+  <arg name="map_path"     default="$(find iri_maps)/maps"/>
   <arg name="map_name"     default="empty"/>
   <arg name="map_frame_id" default="map"/>
   <arg name="map_topic"    default="$(arg ns)/map"/>
@@ -15,7 +16,7 @@
     <node name="map_server" 
           pkg ="map_server" 
           type="map_server"
-          args="$(find iri_maps)/maps/$(arg map_name).yaml"
+          args="$(arg map_path)/$(arg map_name).yaml"
           output="$(arg output)"
           launch-prefix="$(arg launch_prefix)">
       <param name="frame_id" value="$(arg map_frame_id)"/>
diff --git a/launch/nav.launch b/launch/nav.launch
index 8f46e358ba81d54a1b98b47a580f7ba38d6a2517..5a630c937ff97c63e1694d24c4c11f7116c02c86 100644
--- a/launch/nav.launch
+++ b/launch/nav.launch
@@ -17,6 +17,7 @@
   <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_path"                 default="$(find iri_maps)/map"/>
     <arg name="map_name"                 default="willow"/>
   <arg name="use_amcl"                   default="true"/>
     <arg name="amcl_config"              default="$(arg path)/amcl.yaml"/>
@@ -39,6 +40,7 @@
       <include file="$(find iri_rosnav)/launch/include/map_server.launch">
         <arg name="ns"            value="$(arg ns)"/>
         <arg name="map_frame_id"  value="$(arg map_frame_id)"/>
+        <arg name="map_path"      value="$(arg map_path)"/>
         <arg name="map_name"      value="$(arg map_name)"/>
         <arg name="map_topic"     value="$(arg map_topic)"/>
         <arg name="map_service"   value="$(arg map_service)"/>