diff --git a/teleop/launch/teleop.launch b/teleop/launch/teleop.launch
index 20516f1a7928ac77368d5020b94b7466a6cd24f9..1789e359ce191d7f84da95d18bb96d442d4c0030 100644
--- a/teleop/launch/teleop.launch
+++ b/teleop/launch/teleop.launch
@@ -17,6 +17,9 @@
     <param name="square_action_id" type="int" value="-1"/>
     <param name="cross_action_id" type="int" value="16"/>
     <param name="circle_action_id" type="int" value="-1"/>
+    <param name="max_trans_speed"     value="0.04"/>
+    <param name="max_lat_speed"       value="0.04"/>
+    <param name="max_rot_speed"       value="0.2"/>
     <param name="Y_SWAP_AMPLITUDE"    value="0.020"/>
     <param name="Z_SWAP_AMPLITUDE"    value="0.005"/>
     <param name="ARM_SWING_GAIN"      value="1.5"/>
@@ -32,8 +35,8 @@
     <param name="DSP_RATIO"           value="0.1"/>
     <param name="STEP_FB_RATIO"       value="0.28"/>
     <param name="FOOT_HEIGHT"         value="0.04"/>
-    <param name="MAX_VEL"             value="0.01"/>
-    <param name="MAX_ROT_VEL"         value="0.01"/>
+    <param name="MAX_VEL"             value="0.1"/>
+    <param name="MAX_ROT_VEL"         value="0.1"/>
     <param name="pan_p"               value="0.1"/>
     <param name="pan_i"               value="0.0"/>
     <param name="pan_d"               value="0.0"/>
@@ -46,35 +49,35 @@
     <param name="tilt_i_clamp"        value="0.0"/>
     <param name="max_tilt"            value="1.5707"/>
     <param name="min_tilt"            value="-1.5707"/>
-    <remap from="/darwin/action_client/action_client/motion_action"
+    <remap from="/darwin/teleop/action_client/motion_action"
              to="/darwin/robot/motion_action"/>
-    <remap from="/darwin/action_client/action_client/set_servo_modules"
+    <remap from="/darwin/teleop/action_client/set_servo_modules"
              to="/darwin/robot/set_servo_modules"/>
-    <remap from="/darwin/walk_client/walk_client/cmd_vel"
+    <remap from="/darwin/teleop/walk_client/cmd_vel"
              to="/darwin/robot/cmd_vel"/>
-    <remap from="/darwin/walk_client/walk_client/set_walk_params"
+    <remap from="/darwin/teleop/walk_client/set_walk_params"
              to="/darwin/robot/set_walk_params"/>
-    <remap from="/darwin/walk_client/walk_client/get_walk_params"
+    <remap from="/darwin/teleop/walk_client/get_walk_params"
              to="/darwin/robot/get_walk_params"/>
-    <remap from="/darwin/walk_client/walk_client/set_servo_modules"
+    <remap from="/darwin/teleop/walk_client/set_servo_modules"
              to="/darwin/robot/set_servo_modules"/>
-    <remap from="/darwin/walk_client/walk_client/joint_states"
+    <remap from="/darwin/teleop/walk_client/joint_states"
              to="/darwin/joint_states"/>
-    <remap from="/darwin/walk_client/walk_client/fallen_state"
+    <remap from="/darwin/teleop/walk_client/fallen_state"
              to="/darwin/robot/fallen_state"/>
-    <remap from="/darwin/head_tracking_client/head_tracking_client/head_tracking_action"
+    <remap from="/darwin/teleop/head_tracking_client/head_tracking_action"
              to="/darwin/robot/head_follow_target"/>
-    <remap from="/darwin/head_tracking_client/head_tracking_client/head_target"
+    <remap from="/darwin/teleop/head_tracking_client/head_target"
              to="/darwin/robot/head_target"/>
-    <remap from="/darwin/head_tracking_client/head_tracking_client/set_servo_modules"
+    <remap from="/darwin/teleop/head_tracking_client/set_servo_modules"
              to="/darwin/robot/set_servo_modules"/>
-    <remap from="/darwin/head_tracking_client/head_tracking_client/set_pan_pid"
+    <remap from="/darwin/teleop/head_tracking_client/set_pan_pid"
              to="/darwin/robot/set_pan_pid"/>
-    <remap from="/darwin/head_tracking_client/head_tracking_client/get_pan_pid"
+    <remap from="/darwin/teleop/head_tracking_client/get_pan_pid"
              to="/darwin/robot/get_pan_pid"/>
-    <remap from="/darwin/head_tracking_client/head_tracking_client/set_tilt_pid"
+    <remap from="/darwin/teleop/head_tracking_client/set_tilt_pid"
              to="/darwin/robot/set_tilt_pid"/>
-    <remap from="/darwin/head_tracking_client/head_tracking_client/get_tilt_pid"
+    <remap from="/darwin/teleop/head_tracking_client/get_tilt_pid"
              to="/darwin/robot/get_tilt_pid"/>
   </node>
 
@@ -89,9 +92,5 @@
              to="/darwin/teleop/joy"/>
   </node>
 
-  <!-- launch dynamic reconfigure -->
-  <node name="rqt_reconfigure" pkg="rqt_reconfigure" type="rqt_reconfigure" respawn="false"
-    output="screen"/>
-
 </launch>