diff --git a/CMakeLists.txt b/CMakeLists.txt index dd94b41a7dfcc5cb5c88e1b1499fc77ddf5db588..cf96b3652bcb8373e54876205bbec23d0bfe0c0d 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 pal_interaction_msgs moveit_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) diff --git a/include/tiago_modules/tts_module.h b/include/tiago_modules/tts_module.h index 9e59b4a4e4f81a74f0bf507dc4f2f0a2224cb2b6..5b23b18be7e0e6aa8489278ebce0c1a6603b210c 100644 --- a/include/tiago_modules/tts_module.h +++ b/include/tiago_modules/tts_module.h @@ -13,6 +13,25 @@ typedef enum {TTS_MODULE_IDLE,TTS_MODULE_START,TTS_MODULE_WAIT} tts_module_state_t; //Status +/** + * \brief Possible module status returned by the get_status() function + * + * These are the possible status of the module, which are: + * * TTS_MODULE_RUNNING: indicates that the module is active and operating + * properly. + * * TTS_MODULE_SUCCESS: indicates the last navigation goal has been reached + * successfully. + * * TTS_MODULE_ACTION_START_FAIL: indicates that the goal could not be started. + * * TTS_MODULE_TIMEOUT: indicates that the goal did not complete in the + * allowed time. + * * TTS_MODULE_FB_WATCHDOG: indicates that feedback has not been received for + * a long time. + * * TTS_MODULE_ABORTED: indicates that the navigation goal could not be reached. + * * TTS_MODULE_PREEMPTED: indicates that the current navigation goal has been + * canceled by another goal. + * * TTS_MODULE_REJECTED: indicates that the goal informatio is not valid and the + * goal will not be executed. + */ typedef enum {TTS_MODULE_RUNNING, TTS_MODULE_SUCCESS, TTS_MODULE_ACTION_START_FAIL, @@ -23,35 +42,140 @@ typedef enum {TTS_MODULE_RUNNING, TTS_MODULE_REJECTED, TTS_MODULE_INVALID_ID} tts_module_status_t; +/** + * \brief Text to speech module + * + * This module wraps the basics features of the text to speech ROS node in the TIAGO + * robot. It allows to speack any sentence in english and monitor its progress; + * + */ class CTTSModule : public CModule<tts_module::TTSModuleConfig> { private: + /** + * \brief + * + */ tts_module::TTSModuleConfig config; + /** + * \brief + * + */ CModuleAction<pal_interaction_msgs::TtsAction> tts_action; + /** + * \brief + * + */ pal_interaction_msgs::TtsGoal speech_goal; + /** + * \brief + * + */ std::string speaker; //Variables + /** + * \brief + * + */ tts_module_state_t state; + /** + * \brief + * + */ tts_module_status_t status; + /** + * \brief + * + */ bool new_speech; + /** + * \brief + * + */ bool cancel_pending; protected: + /** + * \brief + * + */ void state_machine(void); + /** + * \brief + * + */ void reconfigure_callback(tts_module::TTSModuleConfig &config, uint32_t level); public: //CTTSModule(const std::string &name); + /** + * \brief Constructor + * + */ CTTSModule(const std::string &name,const std::string &name_space=std::string("")); + /** + * \brief Sets the speacker name + * + * This functions set the name of the speacker to use. At the moment, the speacker + * can not be changed, and it is an english male. + * + * \param speacker name of the desired speacker. At the moment this parameter is + * not used. + */ void set_speaker(std::string &speaker); + /** + * \brief Starts a speech process + * + * This function starts a speech. At the moment, the only supported language is + * en_GB, which is the default value, and can not be changed. + * + * \param text the text to speak. + * + * \param language the language identifier ti use. By default this value is set to + * en_GB, which is the only supported language at the moment. + * + * \param delay the time before start speaking in seconds. The defautl value is 0. + */ void say(const std::string &text,const std::string &language=std::string("en_GB"),double delay=0.0); + /** + * \brief Stops the current speech + * + * This functions stops the current speech. This functions signals the stop + * to the speech module, but the is_finished() function must be used to know + * when the head has actually stopped. + * + */ void stop(void); + /** + * \brief Checks if the last speech has finished or not. + * + * This function must be used to know when the last speech has ended, either + * successfully or by any error. + * + * \return a boolean indicating whether the last speech has ended (true) or not + * (false), reagardless of its success or not. + * + */ bool is_finished(void); + /** + * \brief Returns the current state + * + * This function returns the current status of the TTS module. It returns + * one of the tts_module_status_t values. This can be called at any time, but is + * has only meaning when a goal has just finished. + * + * \return the current status of the module. + * + */ tts_module_status_t get_status(void); + /** + * \brief Destructor + * + */ ~CTTSModule(); };