diff --git a/CMakeLists.txt b/CMakeLists.txt
index a8056ba7beb9765398e2496705a0298d0549ad78..65d2e018776ff602513aba17e508b2cd44ac2267 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -7,7 +7,7 @@ project(tiago_modules)
 ## Find catkin macros and libraries
 ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
 ## is used, also find other catkin packages
-find_package(catkin REQUIRED COMPONENTS 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)
+find_package(catkin REQUIRED COMPONENTS 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)
 
 ## System dependencies are found with CMake's conventions
 # find_package(Boost REQUIRED COMPONENTS system)
@@ -92,6 +92,7 @@ generate_dynamic_reconfigure_options(
   cfg/PlayMotionModule.cfg
   cfg/HeadModule.cfg
   cfg/NavModule.cfg
+  cfg/TtsModule.cfg
 )
 
 ###################################
@@ -105,8 +106,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 #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
+ 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
 #  DEPENDS system_lib
 )
 
@@ -211,6 +212,21 @@ target_link_libraries(nav_module ${iriutils_LIBRARY})
 ## either from message generation or dynamic reconfigure
 add_dependencies(nav_module ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
 
+## Declare a C++ library
+add_library(tts_module
+  src/tts_module.cpp
+)
+
+target_link_libraries(tts_module ${catkin_LIBRARIES})
+target_link_libraries(tts_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(tts_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
new file mode 100755
index 0000000000000000000000000000000000000000..8e516b482b0867987858f94dd3a20a24e2197702
--- /dev/null
+++ b/cfg/TtsModule.cfg
@@ -0,0 +1,51 @@
+#! /usr/bin/env python
+#*  All rights reserved.
+#*
+#*  Redistribution and use in source and binary forms, with or without
+#*  modification, are permitted provided that the following conditions
+#*  are met:
+#*
+#*   * Redistributions of source code must retain the above copyright
+#*     notice, this list of conditions and the following disclaimer.
+#*   * Redistributions in binary form must reproduce the above
+#*     copyright notice, this list of conditions and the following
+#*     disclaimer in the documentation and/or other materials provided
+#*     with the distribution.
+#*   * Neither the name of the Willow Garage nor the names of its
+#*     contributors may be used to endorse or promote products derived
+#*     from this software without specific prior written permission.
+#*
+#*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+#*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+#*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+#*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+#*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+#*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+#*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+#*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+#*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+#*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+#*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+#*  POSSIBILITY OF SUCH DAMAGE.
+#***********************************************************
+
+# Author:
+
+PACKAGE='tts_module'
+
+from dynamic_reconfigure.parameter_generator_catkin import *
+
+gen = ParameterGenerator()
+
+play_action = gen.add_group("Play motion 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)
+
+play_action.add("action_max_retries",int_t, 0,                                 "Maximum number of retries fro the action start",    1,   1,    10)
+play_action.add("feedback_watchdog_time_s",double_t,    0,                     "Maximum time between feedback messages",    1,   0.01,    50)
+play_action.add("timeout_s",     double_t,  0,                                 "Maximum time allowed to complete the action",    1,   0.1,    30)
+play_action.add("enable_timeout",bool_t,    0,                                 "Enable action timeout ",         True)
+
+exit(gen.generate(PACKAGE, "TTSModuleAlgorithm", "TTSModule"))
diff --git a/include/tiago_modules/tts_module.h b/include/tiago_modules/tts_module.h
new file mode 100644
index 0000000000000000000000000000000000000000..b7dddd145f6a49e0fc610636b326ea93c4a21dca
--- /dev/null
+++ b/include/tiago_modules/tts_module.h
@@ -0,0 +1,57 @@
+#ifndef _TTS_MODULE_H
+#define _TTS_MODULE_H
+
+#include <iri_ros_tools/module.h> 
+#include <iri_ros_tools/module_action.h>
+
+#include <tiago_modules/TTSModuleConfig.h>
+
+//Action
+#include <pal_interaction_msgs/TtsAction.h>
+
+//States
+typedef enum {TTS_MODULE_IDLE,TTS_MODULE_START,TTS_MODULE_WAIT} tts_module_state_t;
+
+//Status
+typedef enum {TTS_MODULE_SUCCESS,
+              TTS_MODULE_ACTION_START_FAIL,
+              TTS_MODULE_TIMEOUT,
+              TTS_MODULE_FB_WATCHDOG,
+              TTS_MODULE_ABORTED,
+              TTS_MODULE_PREEMPTED,
+              TTS_MODULE_REJECTED,
+              TTS_MODULE_INVALID_ID} tts_module_status_t;
+
+class CTTSModule : public CModule<tts_module::TTSModuleConfig>
+{
+  private:
+
+    tts_module::TTSModuleConfig config;
+
+    CModuleAction<pal_interaction_msgs::TtsAction> tts_action;
+    pal_interaction_msgs::TtsGoal goal;
+
+    //Variables
+    tts_module_state_t state;
+    tts_module_status_t status;
+    bool new_speech;
+    bool cancel_pending;
+
+  protected:
+    void state_machine(void);
+    void reconfigure_callback(tts_module::TTSModuleConfig &config, uint32_t level);
+
+  public:
+    //CTTSModule(const std::string &name);
+    CTTSModule(const std::string &name,const std::string &name_space=std::string(""));
+    void set_language(std::string &language);
+    void set_speaker(std::string &speaker);
+    void say(std::string &text,double delay=0.0);
+    void stop(void);
+    bool is_finished(void);
+    tts_module_status_t get_status(void);
+
+    ~CTTSModule();
+  };
+
+  #endif
diff --git a/package.xml b/package.xml
index 15f3a223ae018dc2a6877de684b0ecc2550ff6ca..6f243bd56f0ee4ab09823b9380794a618f5dcddd 100644
--- a/package.xml
+++ b/package.xml
@@ -52,6 +52,7 @@
   <build_depend>nav_msgs</build_depend>
   <build_depend>pal_navigation_msgs</build_depend>
   <build_depend>pal_waypoint_msgs</build_depend>
+  <build_depend>pal_interaction_msgs</build_depend>
   <build_depend>tf</build_depend>
   <!-- new dependencies -->
   <!--<build_depend>new build dependency</build_depend>-->
@@ -67,6 +68,7 @@
   <run_depend>nav_msgs</run_depend>
   <run_depend>pal_navigation_msgs</run_depend>
   <run_depend>pal_waypoint_msgs</run_depend>
+  <run_depend>pal_interaction_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
new file mode 100644
index 0000000000000000000000000000000000000000..f3b050ddd9d90f0903cfc77db478a319a85d6a15
--- /dev/null
+++ b/src/tts_module.cpp
@@ -0,0 +1,154 @@
+#include <tiago_modules/tts_module.h>
+
+
+CTTSModule::CTTSModule(const std::string &name,const std::string &name_space) : CModule(name,name_space),
+  tts_action("tts",name)
+{
+  this->start_operation();
+
+  //Variables
+  this->state=TTS_MODULE_IDLE;
+  this->status=TTS_MODULE_SUCCESS;
+  this->cancel_pending=false;
+  this->new_speech=false;
+}
+
+/* State machine */
+void CTTSModule::state_machine(void)
+{
+//Action
+  switch(this->state)
+  {
+    case TTS_MODULE_IDLE: ROS_DEBUG("CTTSModule: Idle");
+                          if(this->new_speech)
+                          {
+                            this->new_speech=false;
+                            this->state=TTS_MODULE_START;
+                          }
+                          else
+                            this->state=TTS_MODULE_IDLE;
+                          break;
+
+    case TTS_MODULE_START: ROS_DEBUG("CTTSModule: Start");
+                           switch(this->tts_action.make_request(this->goal))
+                           {
+                             case ACT_SRV_SUCCESS: this->state=TTS_MODULE_WAIT;
+                                                   ROS_DEBUG("CTTSModule : goal start successfull");
+                                                   break;
+                             case ACT_SRV_PENDING: this->state=TTS_MODULE_START;
+                                                   ROS_WARN("CTTSModule : goal start pending");
+                                                   break;
+                             case ACT_SRV_FAIL: this->state=TTS_MODULE_IDLE;
+                                                ROS_ERROR("CTTSModule: goal start failed");
+                                                break;
+                           }
+                           break;
+
+    case TTS_MODULE_WAIT: ROS_DEBUG("CTTSModule : state WAIT");
+                          switch(this->tts_action.get_state())
+                          {
+                            case ACTION_IDLE:
+                            case ACTION_RUNNING: ROS_DEBUG("CTTSModule : action running");
+                                                 this->state=TTS_MODULE_WAIT;
+                                                 break;
+                            case ACTION_SUCCESS: ROS_INFO("CTTSModule : action ended successfully");
+                                                 this->state=TTS_MODULE_IDLE;
+                                                 this->status=TTS_MODULE_SUCCESS;
+                                                 this->tts_action.stop_timeout();
+                                                 break;
+                            case ACTION_TIMEOUT: ROS_ERROR("CTTSModule : action did not finish in the allowed time");
+                                                 this->tts_action.cancel();
+                                                 this->state=TTS_MODULE_IDLE;
+                                                 this->status=TTS_MODULE_TIMEOUT;
+                                                 this->tts_action.stop_timeout();
+                                                 break;
+                            case ACTION_FB_WATCHDOG: ROS_ERROR("CTTSModule : No feeback received for a long time");
+                                                     this->tts_action.cancel();
+                                                     this->state=TTS_MODULE_IDLE;
+                                                     this->status=TTS_MODULE_FB_WATCHDOG;
+                                                     this->tts_action.stop_timeout();
+                                                     break;
+                            case ACTION_ABORTED: ROS_ERROR("CTTSModule : Action failed to complete");
+                                                 this->state=TTS_MODULE_IDLE;
+                                                 this->status=TTS_MODULE_ABORTED;
+                                                 this->tts_action.stop_timeout();
+                                                 break;
+                            case ACTION_PREEMPTED: ROS_ERROR("CTTSModule : Action was interrupted by another request");
+                                                   this->state=TTS_MODULE_IDLE;
+                                                   this->status=TTS_MODULE_PREEMPTED;
+                                                   this->tts_action.stop_timeout();
+                                                   break;
+                            case ACTION_REJECTED: ROS_ERROR("CTTSModule : Action was rejected by server");
+                                                  this->state=TTS_MODULE_IDLE;
+                                                  this->status=TTS_MODULE_REJECTED;
+                                                  this->tts_action.stop_timeout();
+                                                  break;
+                          }
+                          if(this->cancel_pending)
+                          {
+                            this->cancel_pending=false;
+                            this->tts_action.cancel();
+                          }
+                          break;
+  }
+}
+
+void CTTSModule::reconfigure_callback(tts_module::TTSModuleConfig &config, uint32_t level)
+{
+  ROS_INFO("CTTSModule : reconfigure callback");
+  this->lock();
+  this->config=config;
+  /* set the module rate */
+  this->set_rate(config.rate_hz);
+  /* motion action parameters */
+  this->tts_action.set_max_num_retries(config.action_max_retries);
+  this->tts_action.set_feedback_watchdog_time(config.feedback_watchdog_time_s);
+  if(this->config.enable_timeout)
+    this->tts_action.enable_timeout(config.timeout_s);
+  else
+    this->tts_action.disable_timeout(); 
+  this->unlock();
+}
+
+void CTTSModule::set_language(std::string &language)
+{
+
+}
+
+void CTTSModule::set_speaker(std::string &speaker)
+{
+
+}
+
+void CTTSModule::say(std::string &text,double delay)
+{
+
+}
+
+void CTTSModule::stop(void)
+{
+  if(this->state!=TTS_MODULE_IDLE)
+    this->cancel_pending=true;
+}
+
+bool CTTSModule::is_finished(void)
+{
+  if(this->state==TTS_MODULE_IDLE && this->new_speech==false)
+    return true;
+  else
+    return false;
+}
+
+tts_module_status_t CTTSModule::get_status(void)
+{
+  return this->status;
+}
+
+CTTSModule::~CTTSModule()
+{
+  if(!this->tts_action.is_finished())
+  {
+    this->tts_action.cancel();
+    while(!this->tts_action.is_finished());
+  }
+}