diff --git a/launch/fish_eye_camera.launch b/launch/fish_eye_camera.launch
index 92b5c0782d65e53d4c266c1d63bb9ee66e58e23a..d73baabf5f8797e07beea16edaf4666440f8e9b7 100644
--- a/launch/fish_eye_camera.launch
+++ b/launch/fish_eye_camera.launch
@@ -1,26 +1,29 @@
 <?xml version="1.0"?>
 <launch>
- <arg name="dev" default="/dev/video0"/>
- <arg name="w" default="640"/> <!-- 1024 , 640 -->
- <arg name="h" default="480"/> <!-- 768  , 480 -->
- <arg name="camera_info_url" default="$(find iri_visual_gps)/calibration/head_camera_$(arg w)x$(arg h).yaml"/>
- <arg name="exposure"      default="15"/>
- <arg name="white_balance" default="4000"/>
- 
- <node name="usb_cam"
-       pkg ="usb_cam"
-       type="usb_cam_node"
-       output="screen" >
-    <param name="video_device" value="$(arg dev)" />
-    <param name="image_width"  value="$(arg w)" />
-    <param name="image_height" value="$(arg h)" />
-    <param name="pixel_format" value="yuyv" />
+  <arg name="node_name"          default="usb_cam"/>
+  <arg name="dev"                default="/dev/video0"/>
+  <arg name="w"                  default="640"/> <!-- 1024 , 640 -->
+  <arg name="h"                  default="480"/> <!-- 768  , 480 -->
+  <arg name="camera_info_url"    default="$(find iri_visual_gps)/calibration/head_camera_$(arg w)x$(arg h).yaml"/>
+  <arg name="autoexposure"       default="false"/>
+  <arg name="exposure"           default="15"/>
+  <arg name="auto_white_balance" default="false"/>
+  <arg name="white_balance"      default="4000"/>
+
+  <node name="$(arg node_name)"
+        pkg ="usb_cam"
+        type="usb_cam_node"
+        output="screen" >
+    <param name="video_device"    value="$(arg dev)" />
+    <param name="image_width"     value="$(arg w)" />
+    <param name="image_height"    value="$(arg h)" />
+    <param name="pixel_format"    value="yuyv" />
     <param name="camera_frame_id" value="usb_cam" />
-    <param name="io_method" value="mmap"/>
+    <param name="io_method"       value="mmap"/>
     <param name="camera_info_url" value="file://$(arg camera_info_url)"/>
-    <param name="autoexposure"       value="false"/>
+    <param name="autoexposure"       value="$(arg autoexposure)"/>
     <param name="exposure"           value="$(arg exposure)"/>
-    <param name="auto_white_balance" value="false"/>
+    <param name="auto_white_balance" value="$(arg auto_white_balance"/>
     <param name="white_balance"      value="$(arg white_balance)"/>
   </node>