diff --git a/darwin_apps/launch/nav_client_sim.launch b/darwin_apps/launch/nav_client_sim.launch
new file mode 100644
index 0000000000000000000000000000000000000000..02b718798fa908a31ee459836dbd8ace358d7e3a
--- /dev/null
+++ b/darwin_apps/launch/nav_client_sim.launch
@@ -0,0 +1,61 @@
+<launch>
+
+  <arg name="robot" default="darwin" />
+  <arg name="environment" default="obstacles_env_empty" />
+
+  <include file="$(find darwin_description)/launch/darwin_sim.launch">
+    <arg name="robot" value="$(arg robot)" />
+  </include>
+
+  <include file="$(find bioloid_description)/launch/obstacles_env.launch">
+    <arg name="environment" value="$(arg environment)" />
+  </include>
+
+  <include file="$(find darwin_nav)/launch/darwin_global_loc_sim.launch"/>
+
+  <!-- Move Base -->
+  <node pkg="move_base"
+        type="move_base" 
+        name="move_base"
+        output="screen">
+        <remap from="cmd_vel" to="/darwin/robot/cmd_vel"/>
+        <remap from="odom" to="/darwin/robot/odom"/>
+        <!-- Main parameters -->
+        <rosparam file="$(find darwin_nav)/config/move_base_params.yaml" command="load"/>
+        <!-- LOCAL PLANNER -->
+        <rosparam file="$(find darwin_nav)/config/dwa_local_planner_params.yaml" command="load"/>
+        <rosparam file="$(find darwin_nav)/config/costmap_common_params.yaml" command="load" ns="local_costmap"/>
+        <rosparam file="$(find darwin_nav)/config/local_costmap_params.yaml" command="load" ns="local_costmap"/>
+        <!-- GLOBAL PLANNER -->
+        <rosparam file="$(find darwin_nav)/config/global_planner_params.yaml" command="load"/>
+        <rosparam file="$(find darwin_nav)/config/costmap_common_params.yaml" command="load" ns="global_costmap"/>
+        <rosparam file="$(find darwin_nav)/config/global_costmap_params.yaml" command="load" ns="global_costmap"/>
+  </node>
+
+  <!-- launch the navigation client node -->
+  <node name="nav_client"
+        pkg="nav_client"
+        type="nav_client"
+        output="screen"
+        ns="/darwin">
+    <remap from="/darwin/nav_client/nav_client/nav_module/"
+             to="/move_base"/>
+    <remap from="/darwin/nav_client/nav_client/set_servo_modules"
+             to="/darwin/robot/set_servo_modules"/>
+    <remap from="/darwin/nav_client/nav_client/set_walk_params"
+             to="/darwin/robot/set_walk_params"/>
+    <remap from="/darwin/nav_client/nav_client/get_walk_params"
+             to="/darwin/robot/get_walk_params"/>
+    <remap from="/darwin/nav_client/nav_client/joint_states"
+             to="/darwin/joint_states"/>
+    <remap from="/darwin/nav_client/nav_client/fallen_state"
+             to="/darwin/robot/fallen_state"/>
+
+  </node>
+
+  <!-- launch dynamic reconfigure -->
+  <node name="rqt_reconfigure" pkg="rqt_reconfigure" type="rqt_reconfigure" respawn="false"
+    output="screen"/>
+
+</launch>
+
diff --git a/darwin_nav/config/darwin_nav.rviz b/darwin_nav/config/darwin_nav.rviz
index de4a4bf93b06235b15c8bcf246747e3e7707a649..693ab40692e2ab0af006a7b0228a513e4c8d4a42 100644
--- a/darwin_nav/config/darwin_nav.rviz
+++ b/darwin_nav/config/darwin_nav.rviz
@@ -53,18 +53,146 @@ Visualization Manager:
     - Alpha: 1
       Class: rviz/RobotModel
       Collision Enabled: false
-      Enabled: false
+      Enabled: true
       Links:
         All Links Enabled: true
         Expand Joint Details: false
         Expand Link Details: false
         Expand Tree: false
         Link Tree Style: Links in Alphabetic Order
+        base_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        darwin_accel:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        darwin_cam_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        darwin_cam_optical_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        darwin_gyro:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        darwin_imu_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        head:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        left_arm_high:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        left_arm_low:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        left_leg_ankle_pitch:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        left_leg_ankle_roll:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        left_leg_knee:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        left_leg_pelvis_pitch:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        left_leg_pelvis_roll:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        left_leg_pelvis_yaw:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        left_shoulder:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        neck:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        right_arm_high:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        right_arm_low:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        right_leg_ankle_pitch:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        right_leg_ankle_roll:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        right_leg_knee:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        right_leg_pelvis_pitch:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        right_leg_pelvis_roll:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        right_leg_pelvis_yaw:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        right_shoulder:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
       Name: RobotModel
       Robot Description: robot_description
       TF Prefix: /darwin
       Update Interval: 0
-      Value: false
+      Value: true
       Visual Enabled: true
     - Class: rviz/TF
       Enabled: true
@@ -83,12 +211,28 @@ Visualization Manager:
           Value: true
         N125:
           Value: true
+        N125_cam:
+          Value: true
+        N125_det:
+          Value: true
         N175:
           Value: true
+        N175_cam:
+          Value: true
+        N175_det:
+          Value: true
         N25:
           Value: true
+        N25_cam:
+          Value: true
+        N25_det:
+          Value: true
         N75:
           Value: true
+        N75_cam:
+          Value: true
+        N75_det:
+          Value: true
         S125:
           Value: true
         S175:
@@ -234,7 +378,22 @@ Visualization Manager:
                   darwin/head:
                     darwin/darwin_cam_link:
                       darwin/darwin_cam_optical_link:
-                        {}
+                        N125_cam:
+                          {}
+                        N125_det:
+                          {}
+                        N175_cam:
+                          {}
+                        N175_det:
+                          {}
+                        N25_cam:
+                          {}
+                        N25_det:
+                          {}
+                        N75_cam:
+                          {}
+                        N75_det:
+                          {}
                 darwin/right_leg_pelvis_yaw:
                   darwin/right_leg_pelvis_roll:
                     darwin/right_leg_pelvis_pitch:
@@ -253,18 +412,118 @@ Visualization Manager:
     - Alpha: 1
       Class: rviz/RobotModel
       Collision Enabled: false
-      Enabled: false
+      Enabled: true
       Links:
         All Links Enabled: true
+        E125:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        E175:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        E225:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        E25:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        E75:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
         Expand Joint Details: false
         Expand Link Details: false
         Expand Tree: false
         Link Tree Style: Links in Alphabetic Order
+        N125:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        N175:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        N25:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        N75:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        S125:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        S175:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        S25:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        S75:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        W125:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        W175:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        W225:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        W25:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        W75:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        obstacle_base_fence_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        obstacle_base_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
       Name: Environment
       Robot Description: obstacles_environment
       TF Prefix: ""
       Update Interval: 0
-      Value: false
+      Value: true
       Visual Enabled: true
     - Class: rviz/Image
       Enabled: false
@@ -389,22 +648,22 @@ Visualization Manager:
   Views:
     Current:
       Class: rviz/Orbit
-      Distance: 10
+      Distance: 5.08288
       Enable Stereo Rendering:
         Stereo Eye Separation: 0.06
         Stereo Focal Distance: 1
         Swap Stereo Eyes: false
         Value: false
       Focal Point:
-        X: 0
-        Y: 0
-        Z: 0
+        X: 1.38816
+        Y: 1.12817
+        Z: 1.12501
       Name: Current View
       Near Clip Distance: 0.01
-      Pitch: 0.785398
+      Pitch: 0.505398
       Target Frame: <Fixed Frame>
       Value: Orbit (rviz)
-      Yaw: 0.785398
+      Yaw: 0.375398
     Saved: ~
 Window Geometry:
   Displays:
@@ -424,5 +683,5 @@ Window Geometry:
   Views:
     collapsed: false
   Width: 1207
-  X: 65
-  Y: 24
+  X: 55
+  Y: 14