diff --git a/CMakeLists.txt b/CMakeLists.txt
index 5036e2fe2f5f1749db0863f5feddff93d7749616..cf96b3652bcb8373e54876205bbec23d0bfe0c0d 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -93,6 +93,7 @@ generate_dynamic_reconfigure_options(
   cfg/HeadModule.cfg
   cfg/NavModule.cfg
   cfg/TTSModule.cfg
+  cfg/ArmModule.cfg
 )
 
 ###################################
@@ -106,8 +107,8 @@ generate_dynamic_reconfigure_options(
 ## DEPENDS: system dependencies of this project that dependent projects also need
 catkin_package(
  INCLUDE_DIRS include
- LIBRARIES gripper_module play_motion_module head_module torso_module nav_module tts_module#leds_module
- CATKIN_DEPENDS roscpp dynamic_reconfigure iri_ros_tools actionlib play_motion_msgs control_msgs geometry_msgs std_srvs move_base_msgs tf nav_msgs pal_navigation_msgs pal_waypoint_msgs pal_interaction_msgs
+ LIBRARIES gripper_module play_motion_module head_module torso_module nav_module tts_module arm_module#leds_module 
+ CATKIN_DEPENDS roscpp dynamic_reconfigure iri_ros_tools actionlib play_motion_msgs control_msgs geometry_msgs std_srvs move_base_msgs tf nav_msgs pal_navigation_msgs pal_waypoint_msgs pal_interaction_msgs moveit_msgs
 #  DEPENDS system_lib
 )
 
@@ -227,6 +228,21 @@ target_link_libraries(tts_module ${iriutils_LIBRARY})
 ## either from message generation or dynamic reconfigure
 add_dependencies(tts_module ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
 
+## Declare a C++ library
+add_library(arm_module
+  src/arm_module.cpp
+)
+
+target_link_libraries(arm_module ${catkin_LIBRARIES})
+target_link_libraries(arm_module ${iriutils_LIBRARY})
+##Link to other modules
+##target_link_libraries(new_module <module path>/lib<module_name>.so)
+
+## Add cmake target dependencies of the library
+## as an example, code may need to be generated before libraries
+## either from message generation or dynamic reconfigure
+add_dependencies(arm_module ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
+
 ## Declare a C++ executable
 ## With catkin_make all packages are built within a single CMake context
 ## The recommended prefix ensures that target names across packages don't collide
diff --git a/cfg/TTSModule.cfg b/cfg/TTSModule.cfg
index 48174b6c54f83e6e66195d1e6b6f3656108b7eb2..6b6016a5f5ace380b116523ce24e65548d48f4c5 100755
--- a/cfg/TTSModule.cfg
+++ b/cfg/TTSModule.cfg
@@ -41,11 +41,12 @@ tts = gen.add_group("Text to speech action")
 
 #       Name                       Type       Reconfiguration level            Description                       Default   Min   Max
 #gen.add("velocity_scale_factor",  double_t,  0,                               "Maximum velocity scale factor",  0.5,      0.0,  1.0)
-gen.add("rate_hz",                 double_t,  0,                               "TTS module rate in Hz",       1.0,      1.0,  100.0)
+gen.add("rate_hz",                 double_t,  0,                               "TTS module rate in Hz",          1.0,      1.0,  100.0)
 
 tts.add("action_max_retries",      int_t,     0,                               "Maximum number of retries fro the action start",    1,   1,    10)
 tts.add("feedback_watchdog_time_s",double_t,  0,                               "Maximum time between feedback messages",    1,   0.01,    50)
 tts.add("timeout_s",               double_t,  0,                               "Maximum time allowed to complete the action",    1,   0.1,    30)
-tts.add("enable_timeout",          bool_t,    0,                               "Enable action timeout ",         True)
+tts.add("enable_timeout",          bool_t,    0,                               "Enable action timeout",          True)
+tts.add("enabled",                 bool_t,    0,                               "Enable action execution",        True)
 
 exit(gen.generate(PACKAGE, "TTSModuleAlgorithm", "TTSModule"))
diff --git a/package.xml b/package.xml
index 6f243bd56f0ee4ab09823b9380794a618f5dcddd..4d4a9d2f1eecd3576a0d3f24404fd6e81b5bd9f1 100644
--- a/package.xml
+++ b/package.xml
@@ -53,6 +53,7 @@
   <build_depend>pal_navigation_msgs</build_depend>
   <build_depend>pal_waypoint_msgs</build_depend>
   <build_depend>pal_interaction_msgs</build_depend>
+  <build_depend>moveit_msgs</build_depend>
   <build_depend>tf</build_depend>
   <!-- new dependencies -->
   <!--<build_depend>new build dependency</build_depend>-->
@@ -69,6 +70,7 @@
   <run_depend>pal_navigation_msgs</run_depend>
   <run_depend>pal_waypoint_msgs</run_depend>
   <run_depend>pal_interaction_msgs</run_depend>
+  <run_depend>moveit_msgs</run_depend>
   <run_depend>tf</run_depend>
   <!-- new dependencies -->
   <!--<run_depend>new run dependency</run_depend>-->
diff --git a/src/tts_module.cpp b/src/tts_module.cpp
index def71677441d284fd97df2c4d0cbc7665691d762..fd4a849a5d697d7d8f1b11ba906652b2dbf44f66 100644
--- a/src/tts_module.cpp
+++ b/src/tts_module.cpp
@@ -2,7 +2,7 @@
 
 
 CTTSModule::CTTSModule(const std::string &name,const std::string &name_space) : CModule(name,name_space),
-  tts_action("tts",name)
+  tts_action("tts",this->module_nh.getNamespace())
 {
   this->start_operation();
 
@@ -24,6 +24,7 @@ void CTTSModule::state_machine(void)
                           {
                             this->new_speech=false;
                             this->state=TTS_MODULE_START;
+                            this->status=TTS_MODULE_RUNNING;
                           }
                           else
                             this->state=TTS_MODULE_IDLE;
@@ -39,6 +40,7 @@ void CTTSModule::state_machine(void)
                                                    ROS_WARN("CTTSModule : goal start pending");
                                                    break;
                              case ACT_SRV_FAIL: this->state=TTS_MODULE_IDLE;
+                                                this->status=TTS_MODULE_ACTION_START_FAIL;
                                                 ROS_ERROR("CTTSModule: goal start failed");
                                                 break;
                            }
@@ -107,6 +109,10 @@ void CTTSModule::reconfigure_callback(tts_module::TTSModuleConfig &config, uint3
     this->tts_action.enable_timeout(config.timeout_s);
   else
     this->tts_action.disable_timeout(); 
+  if(this->config.enabled)
+    this->tts_action.enable();
+  else
+    this->tts_action.disable();
   this->unlock();
 }