diff --git a/src/darwin_robot.cpp b/src/darwin_robot.cpp
index 67a32e2faf5cfc96b98fdac3ca3e0dc09f2b6fb1..9f512d987870e9aad6a8799213808b6be46839e0 100644
--- a/src/darwin_robot.cpp
+++ b/src/darwin_robot.cpp
@@ -58,7 +58,7 @@ const led_info_t leds[GPIO_NUM_LEDS]={{DARWIN_TX_LED_CNTRL,DARWIN_TX_LED_PERIOD_
                                       {DARWIN_AUX2_LED_CNTRL,DARWIN_AUX2_LED_COLOR_L,GPIO_VALUE_B,GPIO_TOGGLE_B,0x00}};
 
 
-CDarwinRobot::CDarwinRobot(const std::string &name,std::string &bus_id,int bus_speed, unsigned char id)
+CDarwinRobot::CDarwinRobot(const std::string &name,std::string &bus_id,int bus_speed, unsigned char id,bool sim)
 {
   int num_buses;
 
@@ -66,11 +66,22 @@ CDarwinRobot::CDarwinRobot(const std::string &name,std::string &bus_id,int bus_s
   if(name!="")
   {
     this->robot_name=name;
-    this->dyn_server=CDynamixelServerFTDI::instance();
-    num_buses=this->dyn_server->get_num_buses();
+    if(sim)
+    {
+      this->dyn_server=CDynamixelServerSerial::instance();
+      ((CDynamixelServerSerial *)this->dyn_server)->config_bus(bus_id,bus_speed);
+      num_buses=1;
+    }
+    else
+    {
+      this->dyn_server=CDynamixelServerFTDI::instance();
+      num_buses=((CDynamixelServerFTDI *)this->dyn_server)->get_num_buses();
+      if(num_buses>0)
+        ((CDynamixelServerFTDI *)this->dyn_server)->config_bus(bus_id,bus_speed);
+    }
     if(num_buses>0)
     {
-      this->dyn_server->config_bus(bus_id,bus_speed);
+      sleep(1);
       this->robot_device=dyn_server->get_device(id,dyn_version2);
       this->robot_id=id;
       /* wait for the firmware to finish the scan */
diff --git a/src/darwin_robot.h b/src/darwin_robot.h
index 8c3f31a142013abdceaf9c8b6772275962cb4504..632c73bee677001a788e56e13599d29fbffcf87c 100644
--- a/src/darwin_robot.h
+++ b/src/darwin_robot.h
@@ -3,6 +3,7 @@
 
 #include "dynamixel.h"
 #include "dynamixelserver_ftdi.h"
+#include "dynamixelserver_serial.h"
 #include "darwin_registers.h"
 
 #define           MAX_NUM_SERVOS        31
@@ -57,7 +58,7 @@ typedef enum {MM_FWD_FALL=0,MM_BWD_FALL=1,MM_STANDING=2} fall_t;
 class CDarwinRobot
 {
   private:
-    CDynamixelServerFTDI *dyn_server;  
+    CDynamixelServer *dyn_server;
     CDynamixel *robot_device;
     std::string robot_name;
     unsigned char robot_id;
@@ -71,7 +72,7 @@ class CDarwinRobot
     double min_limit_current;
     double max_limit_current;
   public:
-    CDarwinRobot(const std::string &name,std::string &bus_id,int bus_speed, unsigned char id);
+    CDarwinRobot(const std::string &name,std::string &bus_id,int bus_speed, unsigned char id,bool sim=false);
     // GPIO interface
     void gpio_set_led(led_t led);
     void gpio_clear_led(led_t led);
diff --git a/src/examples/darwin_action_test.cpp b/src/examples/darwin_action_test.cpp
index 98fd7dfe3efdc31d13b38a6d51587b236a8c2403..5b11c438f388d2b8b2a833488cfe12928dd1ceb6 100644
--- a/src/examples/darwin_action_test.cpp
+++ b/src/examples/darwin_action_test.cpp
@@ -4,8 +4,8 @@
 
 #include <iostream>
 
-std::string robot_device="A603LOBS";
-//std::string robot_device="A4008atn";
+std::string robot_device="/dev/pts/20";
+//std::string robot_device="A603LOBS";
 
 int main(int argc, char *argv[])
 {
@@ -13,7 +13,7 @@ int main(int argc, char *argv[])
   unsigned int present_servos;
 
   try{
-    CDarwinRobot darwin("Darwin",robot_device,1000000,0x02);
+    CDarwinRobot darwin("Darwin",robot_device,1000000,0x02,true);
 
     num_servos=darwin.mm_get_num_servos();
     present_servos=darwin.mm_get_present_servos();
@@ -36,6 +36,22 @@ int main(int argc, char *argv[])
       std::cout << "action running ... " << std::endl;
       usleep(100000);
     }
+    sleep(2);
+    darwin.action_load_page(SIT_DOWN);
+    darwin.action_start();
+    while(darwin.action_is_page_running())
+    {
+      std::cout << "action running ... " << std::endl;
+      usleep(100000);
+    }
+    sleep(2);
+    darwin.action_load_page(STAND_UP);
+    darwin.action_start();
+    while(darwin.action_is_page_running())
+    {
+      std::cout << "action running ... " << std::endl;
+      usleep(100000);
+    }
     darwin.mm_stop();
     darwin.mm_disable_power();
   }catch(CException &e){