diff --git a/darwin_apps/launch/stairs_client.launch b/darwin_apps/launch/stairs_client.launch
new file mode 100644
index 0000000000000000000000000000000000000000..cdeccaad3fa14f8eaff34fb117f7cd30cd7672cc
--- /dev/null
+++ b/darwin_apps/launch/stairs_client.launch
@@ -0,0 +1,55 @@
+<launch>
+
+  <arg name="robot" default="darwin" />
+
+  <include file="$(find darwin_description)/launch/darwin_base.launch">
+    <arg name="robot" value="$(arg robot)" />
+  </include>
+
+  <!-- launch the stairs client node -->
+  <node name="stairs_client"
+        pkg="stairs_client"
+        type="stairs_client"
+        output="screen"
+        ns="/darwin">
+    <param name="SHIFT_WEIGHT_RIGHT_TIME"    value="1.6"/>
+    <param name="RISE_RIGHT_FOOT_TIME"       value="3.2"/>
+    <param name="ADVANCE_RIGHT_FOOT_TIME"    value="4.8"/>
+    <param name="CONTACT_RIGHT_FOOT_TIME"    value="6.4"/>
+    <param name="SHIFT_WEIGHT_RIGHT_TIME"    value="8.0"/>
+    <param name="RISE_LEFT_FOOT_TIME"        value="9.6"/>
+    <param name="ADVANCE_LEFT_FOOT_TIME"     value="11.2"/>
+    <param name="CONTACT_LEFT_FOOT_TIME"     value="12.8"/>
+    <param name="CENTER_WEIGHT_TIME"         value="14.4"/>
+    <param name="X_OFFSET"                   value="-0.01"/>
+    <param name="Y_OFFSET"                   value="0.005"/>
+    <param name="Z_OFFSET"                   value="0.02"/>
+    <param name="R_OFFSET"                   value="0.0"/>
+    <param name="P_OFFSET"                   value="0.0"/>
+    <param name="A_OFFSET"                   value="0.0"/>
+    <param name="Y_SHIFT"                    value="0.04"/>
+    <param name="X_SHIFT"                    value="0.08"/>
+    <param name="Z_OVERSHOOT"                value="0.015"/>
+    <param name="Z_HEIGHT"                   value="0.03"/>
+    <param name="HIP_PITCH_OFFSET"           value="0.23"/>
+    <param name="R_SHIFT"                    value="0.05"/>
+    <param name="P_SHIFT"                    value="0.1"/>
+    <param name="A_SHIFT"                    value="0.3"/>
+    <param name="Y_SPREAD"                   value="0.02"/>
+    <param name="X_SHIFT_BODY"               value="0.035"/>
+    <remap from="/darwin/stairs_client/stairs_client/climb_stairs"
+             to="/darwin/robot/climb_stairs"/>
+    <remap from="/darwin/stairs_client/stairs_client/set_stairs_params"
+             to="/darwin/robot/set_stairs_params"/>
+    <remap from="/darwin/stairs_client/stairs_client/get_stairs_params"
+             to="/darwin/robot/get_stairs_params"/>
+    <remap from="/darwin/stairs_client/stairs_client/set_servo_modules"
+             to="/darwin/robot/set_servo_modules"/>
+    <remap from="/darwin/stairs_client/stairs_client/fallen_state"
+             to="/darwin/robot/fallen_state"/>
+  </node>
+
+  <include file="$(find ir_foot_sensor)/launch/darwin_two_feet_nodelet.launch">
+  </include>
+</launch>
+
diff --git a/darwin_driver/src/darwin_driver_node.cpp b/darwin_driver/src/darwin_driver_node.cpp
index f899e96d70fdc289f817d454a2931fced0e2e1ef..c086f9210406c08d9677bb4698fe2937cdd286c5 100644
--- a/darwin_driver/src/darwin_driver_node.cpp
+++ b/darwin_driver/src/darwin_driver_node.cpp
@@ -34,7 +34,7 @@ const std::string servo_names[MAX_NUM_SERVOS]={std::string("Servo0"),
 
 DarwinDriverNode::DarwinDriverNode(ros::NodeHandle &nh) : 
   iri_base_driver::IriBaseNodeDriver<DarwinDriver>(nh),
-  climb_stairs_aserver_(public_node_handle_, "climb_stairs"),
+  climb_stairs_aserver_(public_node_handle_, "robot/climb_stairs"),
   joint_trajectory_aserver_(public_node_handle_, "robot/joint_trajectory"),
   head_follow_target_aserver_(public_node_handle_, "robot/head_follow_target"),
   motion_action_aserver_(public_node_handle_, "robot/motion_action")
@@ -61,10 +61,10 @@ DarwinDriverNode::DarwinDriverNode(ros::NodeHandle &nh) :
 
   
   // [init services]
-  this->get_stairs_params_server_ = this->public_node_handle_.advertiseService("get_stairs_params", &DarwinDriverNode::get_stairs_paramsCallback, this);
+  this->get_stairs_params_server_ = this->public_node_handle_.advertiseService("robot/get_stairs_params", &DarwinDriverNode::get_stairs_paramsCallback, this);
   pthread_mutex_init(&this->get_stairs_params_mutex_,NULL);
 
-  this->set_stairs_params_server_ = this->public_node_handle_.advertiseService("set_stairs_params", &DarwinDriverNode::set_stairs_paramsCallback, this);
+  this->set_stairs_params_server_ = this->public_node_handle_.advertiseService("robot/set_stairs_params", &DarwinDriverNode::set_stairs_paramsCallback, this);
   pthread_mutex_init(&this->set_stairs_params_mutex_,NULL);
 
 // Get smart charger module configuration