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_controller/src/sim/stm32_dyn_master_v2_servos.c b/darwin_controller/src/sim/stm32_dyn_master_v2_servos.c
index 644fa60d65f6db90bbf75b4943b31b3779fbec36..6f3f61726cd78112e2a22589c4e98b49e4e8845e 100644
--- a/darwin_controller/src/sim/stm32_dyn_master_v2_servos.c
+++ b/darwin_controller/src/sim/stm32_dyn_master_v2_servos.c
@@ -7,11 +7,12 @@ void darwin_dyn_master_v2_init(void)
   darwin_dyn_master_v2.version=DYN_VER2;
 }
 
-void darwin_dyn_master_v2_enable_power(void)
+inline void darwin_dyn_master_v2_enable_power(void)
 {
+  /* do nothing */
 }
 
-void darwin_dyn_master_v2_disable_power(void)
+inline void darwin_dyn_master_v2_disable_power(void)
 {
+  /* do nothing */
 }
-
diff --git a/darwin_description/launch/darwin_base_sim.launch b/darwin_description/launch/darwin_base_sim.launch
index 7a2288bf912c3a39165c92724d9c1a06f560ab51..e5d86f1fc812e313a4de9a385e12091618a26862 100644
--- a/darwin_description/launch/darwin_base_sim.launch
+++ b/darwin_description/launch/darwin_base_sim.launch
@@ -17,5 +17,6 @@
   <node name="rviz" 
         pkg="rviz" 
         type="rviz" 
-        args="-d $(find darwin_description)/config/darwin_rviz.rviz"/>
+        args="-d $(find darwin_nav)/config/darwin_nav.rviz"/>
+<!--        args="-d $(find darwin_description)/config/darwin_rviz.rviz"/>-->
 </launch>
diff --git a/darwin_description/launch/environment.launch b/darwin_description/launch/environment.launch
index d13bf0e8fd0c42a2efab784c223ab6f8a668de64..bf5d15c835d26ebd8ac33daf5270ec3cf868ae9b 100644
--- a/darwin_description/launch/environment.launch
+++ b/darwin_description/launch/environment.launch
@@ -1,7 +1,6 @@
 <launch>
-  <arg name="environment" default="charge_env" />
 
-  <group ns="$(arg environment)"> 
+  <group ns="charge_env"> 
     <!-- Convert an xacro and put on parameter server -->
     <param name="robot_description"
            command="$(find xacro)/xacro --inorder '$(find bioloid_description)/urdf/ceabot/$(arg environment).xacro'" />
diff --git a/darwin_description/urdf/charge/charge_env.xacro b/darwin_description/urdf/charge/charge_env.xacro
index c2dc91d50fd028e9442c1216fd1fd5b5d2413bc2..f6606926ac2faf69cd41f1e0dd4674286cdbdced 100755
--- a/darwin_description/urdf/charge/charge_env.xacro
+++ b/darwin_description/urdf/charge/charge_env.xacro
@@ -1,5 +1,6 @@
 <robot name="bioloid" xmlns:xacro="http://www.ros.org/wiki/xacro">
  
+  <xacro:include filename="$(find bioloid_description)/urdf/materials.xacro" />
   <xacro:include filename="$(find bioloid_description)/urdf/ceabot/obstacle_base.xacro" />
   <xacro:include filename="$(find darwin_description)/urdf/charge/charge_station.xacro" />
 
diff --git a/darwin_description/urdf/charge/charge_station.xacro b/darwin_description/urdf/charge/charge_station.xacro
index d966460c2e4afeacaa5a86086dacf06d564b6ea5..6c38e700f6105321eaf7304117350410a9fcfd18 100644
--- a/darwin_description/urdf/charge/charge_station.xacro
+++ b/darwin_description/urdf/charge/charge_station.xacro
@@ -17,6 +17,7 @@
         <geometry>
           <mesh filename="package://darwin_description/meshes/charge/charge_support.stl"/>
         </geometry>
+        <material name="grey"/>
       </visual>
       <collision>
         <origin xyz="0 0 0" rpy="0 0 0"/>
@@ -44,6 +45,7 @@
         <geometry>
           <mesh filename="package://darwin_description/meshes/charge/far_qr.stl"/>
         </geometry>
+        <material name="white"/>
       </visual>
       <collision>
         <origin xyz="0 0 0" rpy="0 0 0"/>
@@ -88,6 +90,7 @@
           <cylinder radius="0.2" length="0.02"/>
           <!--          <mesh filename="package://darwin_description/meshes/charge/connector.stl"/> -->
         </geometry>
+        <material name="white"/>
       </visual>
       <collision>
         <origin xyz="0 0 0" rpy="0 0 0"/>
@@ -116,6 +119,7 @@
         <geometry>
           <mesh filename="package://darwin_description/meshes/charge/near_qr.stl"/>
         </geometry>
+        <material name="white"/>
       </visual>
       <collision>
         <origin xyz="0 0 0" rpy="0 0 0"/>
diff --git a/darwin_nav/config/darwin_nav.rviz b/darwin_nav/config/darwin_nav.rviz
new file mode 100644
index 0000000000000000000000000000000000000000..693ab40692e2ab0af006a7b0228a513e4c8d4a42
--- /dev/null
+++ b/darwin_nav/config/darwin_nav.rviz
@@ -0,0 +1,687 @@
+Panels:
+  - Class: rviz/Displays
+    Help Height: 78
+    Name: Displays
+    Property Tree Widget:
+      Expanded:
+        - /Global Options1
+        - /TF1/Frames1
+        - /TF1/Tree1
+        - /local_plan1
+      Splitter Ratio: 0.385563
+    Tree Height: 655
+  - Class: rviz/Selection
+    Name: Selection
+  - Class: rviz/Tool Properties
+    Expanded:
+      - /2D Pose Estimate1
+      - /2D Nav Goal1
+      - /Publish Point1
+    Name: Tool Properties
+    Splitter Ratio: 0.588679
+  - Class: rviz/Views
+    Expanded:
+      - /Current View1
+    Name: Views
+    Splitter Ratio: 0.5
+  - Class: rviz/Time
+    Experimental: false
+    Name: Time
+    SyncMode: 0
+    SyncSource: ""
+Visualization Manager:
+  Class: ""
+  Displays:
+    - Alpha: 0.5
+      Cell Size: 1
+      Class: rviz/Grid
+      Color: 160; 160; 164
+      Enabled: true
+      Line Style:
+        Line Width: 0.03
+        Value: Lines
+      Name: Grid
+      Normal Cell Count: 0
+      Offset:
+        X: 0
+        Y: 0
+        Z: 0
+      Plane: XY
+      Plane Cell Count: 10
+      Reference Frame: <Fixed Frame>
+      Value: true
+    - Alpha: 1
+      Class: rviz/RobotModel
+      Collision 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: true
+      Visual Enabled: true
+    - Class: rviz/TF
+      Enabled: true
+      Frame Timeout: 15
+      Frames:
+        All Enabled: true
+        E125:
+          Value: true
+        E175:
+          Value: true
+        E225:
+          Value: true
+        E25:
+          Value: true
+        E75:
+          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:
+          Value: true
+        S25:
+          Value: true
+        S75:
+          Value: true
+        W125:
+          Value: true
+        W175:
+          Value: true
+        W225:
+          Value: true
+        W25:
+          Value: true
+        W75:
+          Value: true
+        darwin/base_footprint:
+          Value: true
+        darwin/base_link:
+          Value: true
+        darwin/darwin_accel:
+          Value: true
+        darwin/darwin_cam_link:
+          Value: true
+        darwin/darwin_cam_optical_link:
+          Value: true
+        darwin/darwin_gyro:
+          Value: true
+        darwin/darwin_imu_link:
+          Value: true
+        darwin/head:
+          Value: true
+        darwin/left_arm_high:
+          Value: true
+        darwin/left_arm_low:
+          Value: true
+        darwin/left_leg_ankle_pitch:
+          Value: true
+        darwin/left_leg_ankle_roll:
+          Value: true
+        darwin/left_leg_knee:
+          Value: true
+        darwin/left_leg_pelvis_pitch:
+          Value: true
+        darwin/left_leg_pelvis_roll:
+          Value: true
+        darwin/left_leg_pelvis_yaw:
+          Value: true
+        darwin/left_shoulder:
+          Value: true
+        darwin/neck:
+          Value: true
+        darwin/odom:
+          Value: true
+        darwin/right_arm_high:
+          Value: true
+        darwin/right_arm_low:
+          Value: true
+        darwin/right_leg_ankle_pitch:
+          Value: true
+        darwin/right_leg_ankle_roll:
+          Value: true
+        darwin/right_leg_knee:
+          Value: true
+        darwin/right_leg_pelvis_pitch:
+          Value: true
+        darwin/right_leg_pelvis_roll:
+          Value: true
+        darwin/right_leg_pelvis_yaw:
+          Value: true
+        darwin/right_shoulder:
+          Value: true
+        obstacle_base_fence_link:
+          Value: true
+        obstacle_base_link:
+          Value: true
+      Marker Scale: 0.2
+      Name: TF
+      Show Arrows: true
+      Show Axes: true
+      Show Names: true
+      Tree:
+        obstacle_base_link:
+          E125:
+            {}
+          E175:
+            {}
+          E225:
+            {}
+          E25:
+            {}
+          E75:
+            {}
+          N125:
+            {}
+          N175:
+            {}
+          N25:
+            {}
+          N75:
+            {}
+          S125:
+            {}
+          S175:
+            {}
+          S25:
+            {}
+          S75:
+            {}
+          W125:
+            {}
+          W175:
+            {}
+          W225:
+            {}
+          W25:
+            {}
+          W75:
+            {}
+          darwin/odom:
+            darwin/base_footprint:
+              darwin/base_link:
+                darwin/darwin_accel:
+                  {}
+                darwin/darwin_gyro:
+                  {}
+                darwin/darwin_imu_link:
+                  {}
+                darwin/left_leg_pelvis_yaw:
+                  darwin/left_leg_pelvis_roll:
+                    darwin/left_leg_pelvis_pitch:
+                      darwin/left_leg_knee:
+                        darwin/left_leg_ankle_pitch:
+                          darwin/left_leg_ankle_roll:
+                            {}
+                darwin/left_shoulder:
+                  darwin/left_arm_high:
+                    darwin/left_arm_low:
+                      {}
+                darwin/neck:
+                  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:
+                      darwin/right_leg_knee:
+                        darwin/right_leg_ankle_pitch:
+                          darwin/right_leg_ankle_roll:
+                            {}
+                darwin/right_shoulder:
+                  darwin/right_arm_high:
+                    darwin/right_arm_low:
+                      {}
+          obstacle_base_fence_link:
+            {}
+      Update Interval: 0
+      Value: true
+    - Alpha: 1
+      Class: rviz/RobotModel
+      Collision 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: true
+      Visual Enabled: true
+    - Class: rviz/Image
+      Enabled: false
+      Image Topic: /darwin/camera/image_raw
+      Max Value: 1
+      Median window: 5
+      Min Value: 0
+      Name: Image
+      Normalize Range: true
+      Queue Size: 2
+      Transport Hint: compressed
+      Unreliable: false
+      Value: false
+    - Alpha: 0.7
+      Class: rviz/Map
+      Color Scheme: map
+      Draw Behind: false
+      Enabled: false
+      Name: local_costmap
+      Topic: /move_base/local_costmap/costmap
+      Unreliable: false
+      Value: false
+    - Alpha: 0.7
+      Class: rviz/Map
+      Color Scheme: map
+      Draw Behind: false
+      Enabled: false
+      Name: global_costmap
+      Topic: /move_base/global_costmap/costmap
+      Unreliable: false
+      Value: false
+    - Alpha: 1
+      Buffer Length: 1
+      Class: rviz/Path
+      Color: 25; 255; 0
+      Enabled: true
+      Head Diameter: 0.3
+      Head Length: 0.2
+      Length: 0.3
+      Line Style: Lines
+      Line Width: 0.03
+      Name: global_plan
+      Offset:
+        X: 0
+        Y: 0
+        Z: 0
+      Pose Color: 255; 85; 255
+      Pose Style: None
+      Radius: 0.03
+      Shaft Diameter: 0.1
+      Shaft Length: 0.1
+      Topic: /move_base/GlobalPlanner/plan
+      Unreliable: false
+      Value: true
+    - Alpha: 1
+      Buffer Length: 1
+      Class: rviz/Path
+      Color: 0; 0; 255
+      Enabled: true
+      Head Diameter: 0.3
+      Head Length: 0.2
+      Length: 0.3
+      Line Style: Lines
+      Line Width: 0.03
+      Name: local_plan
+      Offset:
+        X: 0
+        Y: 0
+        Z: 0
+      Pose Color: 255; 85; 255
+      Pose Style: None
+      Radius: 0.03
+      Shaft Diameter: 0.1
+      Shaft Length: 0.1
+      Topic: /move_base/DWAPlannerROS/local_plan
+      Unreliable: false
+      Value: true
+    - Alpha: 1
+      Buffer Length: 1
+      Class: rviz/Path
+      Color: 255; 0; 0
+      Enabled: true
+      Head Diameter: 0.3
+      Head Length: 0.2
+      Length: 0.3
+      Line Style: Lines
+      Line Width: 0.03
+      Name: local_global_plan
+      Offset:
+        X: 0
+        Y: 0
+        Z: 0
+      Pose Color: 255; 85; 255
+      Pose Style: None
+      Radius: 0.03
+      Shaft Diameter: 0.1
+      Shaft Length: 0.1
+      Topic: /move_base/DWAPlannerROS/global_plan
+      Unreliable: false
+      Value: true
+  Enabled: true
+  Global Options:
+    Background Color: 48; 48; 48
+    Fixed Frame: obstacle_base_link
+    Frame Rate: 30
+  Name: root
+  Tools:
+    - Class: rviz/Interact
+      Hide Inactive Objects: true
+    - Class: rviz/MoveCamera
+    - Class: rviz/Select
+    - Class: rviz/FocusCamera
+    - Class: rviz/Measure
+    - Class: rviz/SetInitialPose
+      Topic: /darwin/qr_global_loc/initialpose
+    - Class: rviz/SetGoal
+      Topic: /move_base_simple/goal
+    - Class: rviz/PublishPoint
+      Single click: true
+      Topic: /clicked_point
+  Value: true
+  Views:
+    Current:
+      Class: rviz/Orbit
+      Distance: 5.08288
+      Enable Stereo Rendering:
+        Stereo Eye Separation: 0.06
+        Stereo Focal Distance: 1
+        Swap Stereo Eyes: false
+        Value: false
+      Focal Point:
+        X: 1.38816
+        Y: 1.12817
+        Z: 1.12501
+      Name: Current View
+      Near Clip Distance: 0.01
+      Pitch: 0.505398
+      Target Frame: <Fixed Frame>
+      Value: Orbit (rviz)
+      Yaw: 0.375398
+    Saved: ~
+Window Geometry:
+  Displays:
+    collapsed: false
+  Height: 936
+  Hide Left Dock: false
+  Hide Right Dock: false
+  Image:
+    collapsed: false
+  QMainWindow State: 000000ff00000000fd00000004000000000000016a0000031efc0200000008fb0000001200530065006c0065006300740069006f006e00000000280000009b0000006400fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000280000031e000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006500000002190000012d0000001600ffffff000000010000010f0000031efc0200000004fb0000001e0054006f006f006c002000500072006f007000650072007400690065007301000000280000006e0000006400fffffffb0000000a00560069006500770073010000009c000002aa000000b000fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073010000031b000000a30000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b70000003efc0100000002fb0000000800540069006d00650100000000000004b7000002f600fffffffb0000000800540069006d00650100000000000004500000000000000000000002320000031e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  Selection:
+    collapsed: false
+  Time:
+    collapsed: false
+  Tool Properties:
+    collapsed: false
+  Views:
+    collapsed: false
+  Width: 1207
+  X: 55
+  Y: 14
diff --git a/darwin_nav/config/dwa_local_planner_params.yaml b/darwin_nav/config/dwa_local_planner_params.yaml
index 974a25acfca4ce4cd26e982e86f5dfea5a953b46..391b477659d707d2bcdeba5d06a6542c2e9fdcc4 100644
--- a/darwin_nav/config/dwa_local_planner_params.yaml
+++ b/darwin_nav/config/dwa_local_planner_params.yaml
@@ -1,18 +1,18 @@
 base_local_planner: "dwa_local_planner/DWAPlannerROS"
 
 DWAPlannerROS:
-  max_trans_vel: 0.24
+  max_trans_vel: 0.1
   min_trans_vel: 0.01
-  max_vel_x: 0.24 
-  min_vel_x: -0.24 
+  max_vel_x: 0.1 
+  min_vel_x: -0.1 
   max_vel_y: 0.1 
   min_vel_y: -0.1
-  max_rot_vel: 0.1
-  min_rot_vel: 0.01 
+  max_rot_vel: 0.4
+  min_rot_vel: 0.1 
 
-  sim_time: 3
+  sim_time: 10
   sim_granularity: 0.025
-  angular_sim_granularity: 0.1
+  angular_sim_granularity: 0.01
 
   path_distance_bias: 32.0
   goal_distance_bias: 24.0
@@ -26,19 +26,19 @@ DWAPlannerROS:
   scaling_speed: 0.25
   max_scaling_factor: 0.2
 
-  vx_samples: 10
-  vy_samples: 10 
+  vx_samples: 21
+  vy_samples: 1 
   vth_samples: 20
 
-  acc_lim_theta: 0.1 
-  acc_lim_x: 0.1 
-  acc_lim_y: 0.1
-  acc_limit_trans: 0.1
+  acc_lim_theta: 0.3 
+  acc_lim_x: 0.3
+  acc_lim_y: 0.3
+  acc_limit_trans: 0.3
 
   rot_stopped_vel: 0.01
   trans_stopped_vel: 0.01
 
-  xy_goal_tolerance: 0.05
+  xy_goal_tolerance: 0.1
   yaw_goal_tolerance: 0.05
 
   #not in dynamic reconfigure
@@ -46,7 +46,7 @@ DWAPlannerROS:
   publish_cost_grid_pc: false #true, useful to play with goal/path_distance_bias parameters
 
 #move_base namespace
-  latch_xy_goal_tolerance: true #false
+latch_xy_goal_tolerance: true #false
 
   #prune_plan: true
   #use_dwa: true
diff --git a/darwin_nav/launch/darwin_global_loc_sim.launch b/darwin_nav/launch/darwin_global_loc_sim.launch
index fc3a97d82ae5cc20bf916a0a59109e5b2dcffa1b..b4a952c4411facdbdf9d4203cfbf144d57d5405a 100644
--- a/darwin_nav/launch/darwin_global_loc_sim.launch
+++ b/darwin_nav/launch/darwin_global_loc_sim.launch
@@ -5,9 +5,9 @@
           name="qr_detector"
           type="qr_detector"
           output="screen">
-      <param name="qr_x" value="0.14"/>
-      <param name="qr_y" value="0.14"/>
-      <param name="camera_frame" value="/darwin/darwin_cam_optical_link"/>
+      <param name="qr_x" value="0.2"/>
+      <param name="qr_y" value="0.2"/>
+      <param name="camera_frame" value="/darwin/darwin_cam_link"/>
       <remap from="~/camera/image_raw" to="/darwin/camera/image_raw"/>
       <remap from="~/camera/camera_info" to="/darwin/camera/camera_info"/>
     </node>
@@ -16,7 +16,7 @@
           name="qr_global_loc"
           type="qr_global_loc"
           output="screen">
-      <param name="qr_map_param" value="/obstacles_env_empty/robot_description"/>
+      <param name="qr_map_param" value="/obstacles_environment"/>
       <param name="tf_prefix" value="/darwin"/>
       <param name="publish_tf" value="True"/>
       <param name="publish_rate" value="20"/>
diff --git a/darwin_nav/launch/darwin_nav_sim.launch b/darwin_nav/launch/darwin_nav_sim.launch
index 3cf80c4aa63c9f1fc26161eba304618058f1021e..0d1e93eb334bb4521ce9ecca961edf5d5669acd1 100644
--- a/darwin_nav/launch/darwin_nav_sim.launch
+++ b/darwin_nav/launch/darwin_nav_sim.launch
@@ -2,13 +2,13 @@
 <launch>
 
   <arg name="robot" default="darwin" />
-  <arg name="environment" default="charge_env" />
+  <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 darwin_description)/launch/charge_env.launch">
+  <include file="$(find bioloid_description)/launch/obstacles_env.launch">
     <arg name="environment" value="$(arg environment)" />
   </include>
 
diff --git a/darwin_odometry/src/darwin_odometry_alg_node.cpp b/darwin_odometry/src/darwin_odometry_alg_node.cpp
index 0fd98cf9bc7a0007fd7293dcf378d1194568f8d2..b942af893abd1ddced4e393df513e63e5c605902 100644
--- a/darwin_odometry/src/darwin_odometry_alg_node.cpp
+++ b/darwin_odometry/src/darwin_odometry_alg_node.cpp
@@ -112,7 +112,7 @@ void DarwinOdometryAlgNode::joint_states_callback(const sensor_msgs::JointState:
       odom_trans.transform.translation.x = 0.0;
       odom_trans.transform.translation.y = 0.0;
       odom_trans.transform.translation.z = odom_pos[2];
-      odom_trans.transform.rotation = tf::createQuaternionMsgFromRollPitchYaw(odom_rot[0],odom_rot[1],0.0);
+      odom_trans.transform.rotation = tf::createQuaternionMsgFromRollPitchYaw(odom_rot[0],odom_rot[1],1.5707);
       this->odom_broadcaster.sendTransform(odom_trans);
       odom_trans.header.frame_id = this->config_.tf_prefix+"/odom";
       odom_trans.child_frame_id = this->config_.tf_prefix+"/base_footprint";
@@ -120,7 +120,7 @@ void DarwinOdometryAlgNode::joint_states_callback(const sensor_msgs::JointState:
       odom_trans.transform.translation.x = odom_pos[0];
       odom_trans.transform.translation.y = odom_pos[1];
       odom_trans.transform.translation.z = 0.0;
-      odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(odom_rot[2]);
+      odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(odom_rot[2]-1.5707);
       this->odom_broadcaster.sendTransform(odom_trans);
     }
   }catch(CException &e){