diff --git a/CMakeLists.txt b/CMakeLists.txt index 7afd1f6ecc9bdfa8581814875b98e4d139ac2eb8..c019c8951078be1f717ea67208963e8033726492 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -107,8 +107,9 @@ 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 arm_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 + 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 ) diff --git a/include/tiago_modules/tts_module.h b/include/tiago_modules/tts_module.h index 5b23b18be7e0e6aa8489278ebce0c1a6603b210c..8cb975fc110809c0e665cc75d5d4587377a6ad1b 100644 --- a/include/tiago_modules/tts_module.h +++ b/include/tiago_modules/tts_module.h @@ -1,7 +1,7 @@ #ifndef _TTS_MODULE_H #define _TTS_MODULE_H -#include <iri_ros_tools/module.h> +#include <iri_ros_tools/module.h> #include <iri_ros_tools/module_action.h> #include <tiago_modules/TTSModuleConfig.h> @@ -15,19 +15,19 @@ typedef enum {TTS_MODULE_IDLE,TTS_MODULE_START,TTS_MODULE_WAIT} tts_module_state //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 + * * 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 + * * 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. @@ -55,57 +55,57 @@ class CTTSModule : public CModule<tts_module::TTSModuleConfig> /** * \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); @@ -113,12 +113,12 @@ class CTTSModule : public CModule<tts_module::TTSModuleConfig> //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. * @@ -128,15 +128,15 @@ class CTTSModule : public CModule<tts_module::TTSModuleConfig> 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. - * + * + * 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 + * + * \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); @@ -144,37 +144,37 @@ class CTTSModule : public CModule<tts_module::TTSModuleConfig> * \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 + * 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 + * 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 + * \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 + * 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(); };