Provides text-to-phonemes/words sythesis via Festival. More...
#include <FestivalGenerator.h>
Public Slots | |
| void | run () |
Public Member Functions | |
| void | callbackSynth (const std_msgs::String::ConstPtr &msg) |
| void | callbackTalkingFinished (const std_msgs::String::ConstPtr &msg) |
| FestivalGenerator (QObject *parent=0) | |
| void | subscribeWithNodeHandle (ros::NodeHandle node_handle) |
| subscribe to topics here | |
| ~FestivalGenerator () | |
Private Member Functions | |
| std::string | clearSmileys (std::string text) |
| std::string | prepareText (std::string text) |
| void | synthPhonemes (std::string text) |
| Synthesize phonemes for given text. | |
| void | synthWords (std::string text) |
| Synthesize words for given text. | |
| std::string | trimSpaces (std::string text) |
Private Attributes | |
| ros::Publisher | phonemes_publisher_ |
| Define your custom ROS subscribers, callbacks and publishers here. | |
| bool | publish_smiley_ |
| std::vector< std::string > | punctuation_characters_ |
| std::vector< std::string > | smileys_ |
| ros::Subscriber | subscriber_ |
| bool | synth_phonemes_ |
| bool | synth_words_ |
| ros::Subscriber | talking_finished_subscriber_ |
| std::string | text_for_synth_ |
| QTimer * | timer_ |
Provides text-to-phonemes/words sythesis via Festival.
Definition at line 46 of file FestivalGenerator.h.
| FestivalGenerator::FestivalGenerator | ( | QObject * | parent = 0 | ) | [explicit] |
Constructor
Definition at line 26 of file FestivalGenerator.cpp.
Destructor
Definition at line 67 of file FestivalGenerator.cpp.
| void FestivalGenerator::callbackSynth | ( | const std_msgs::String::ConstPtr & | msg | ) |
Definition at line 99 of file FestivalGenerator.cpp.
| void FestivalGenerator::callbackTalkingFinished | ( | const std_msgs::String::ConstPtr & | msg | ) |
Definition at line 109 of file FestivalGenerator.cpp.
| std::string FestivalGenerator::clearSmileys | ( | std::string | text | ) | [private] |
Definition at line 173 of file FestivalGenerator.cpp.
| std::string FestivalGenerator::prepareText | ( | std::string | text | ) | [private] |
Definition at line 140 of file FestivalGenerator.cpp.
| void FestivalGenerator::run | ( | ) | [slot] |
Definition at line 72 of file FestivalGenerator.cpp.
| void FestivalGenerator::subscribeWithNodeHandle | ( | ros::NodeHandle | node_handle | ) |
subscribe to topics here
Definition at line 131 of file FestivalGenerator.cpp.
| void FestivalGenerator::synthPhonemes | ( | std::string | text | ) | [private] |
Synthesize phonemes for given text.
Definition at line 114 of file FestivalGenerator.cpp.
| void FestivalGenerator::synthWords | ( | std::string | text | ) | [private] |
Synthesize words for given text.
Definition at line 122 of file FestivalGenerator.cpp.
| std::string FestivalGenerator::trimSpaces | ( | std::string | text | ) | [private] |
Definition at line 194 of file FestivalGenerator.cpp.
ros::Publisher FestivalGenerator::phonemes_publisher_ [private] |
Define your custom ROS subscribers, callbacks and publishers here.
Definition at line 78 of file FestivalGenerator.h.
bool FestivalGenerator::publish_smiley_ [private] |
Definition at line 69 of file FestivalGenerator.h.
std::vector<std::string> FestivalGenerator::punctuation_characters_ [private] |
Definition at line 72 of file FestivalGenerator.h.
std::vector<std::string> FestivalGenerator::smileys_ [private] |
Definition at line 73 of file FestivalGenerator.h.
ros::Subscriber FestivalGenerator::subscriber_ [private] |
Definition at line 79 of file FestivalGenerator.h.
bool FestivalGenerator::synth_phonemes_ [private] |
Definition at line 67 of file FestivalGenerator.h.
bool FestivalGenerator::synth_words_ [private] |
Definition at line 68 of file FestivalGenerator.h.
ros::Subscriber FestivalGenerator::talking_finished_subscriber_ [private] |
Definition at line 80 of file FestivalGenerator.h.
std::string FestivalGenerator::text_for_synth_ [private] |
Definition at line 70 of file FestivalGenerator.h.
QTimer* FestivalGenerator::timer_ [private] |
Definition at line 75 of file FestivalGenerator.h.