11 #include <speak_lib.h> 13 #include <std_msgs/String.h> 14 #include <boost/thread.hpp> 15 #include <boost/thread/mutex.hpp> 17 #include <dynamic_reconfigure/server.h> 18 #include <espeak_ros/EspeakConfig.h> 29 boost::mutex::scoped_lock u_lock(
mtx);
31 ROS_INFO(
"[espeak_node]: speaking \"%s\"", line->data.c_str());
32 espeak_Synth(line->data.c_str(), line->data.length()+1, 0, POS_CHARACTER, 0,
33 espeakCHARS_AUTO | espeakPHONEMES | espeakENDPAUSE, NULL, NULL);
38 int main(
int argc,
char** argv ) {
39 espeak_Initialize(AUDIO_OUTPUT_PLAYBACK, 0, NULL, 0);
48 std::string voice_name;
52 espeak_VOICE voice_select;
55 int rate, volume, pitch, range, punctuation;
56 int voice_num, dialect_num, capitals, wordgap, age, gender;
59 rate = espeak_GetParameter(espeakRATE, 0);
60 volume = espeak_GetParameter(espeakVOLUME, 0);
61 pitch = espeak_GetParameter(espeakPITCH, 0);
62 range = espeak_GetParameter(espeakRANGE, 0);
63 punctuation = espeak_GetParameter(espeakPUNCTUATION, 0);
64 capitals = espeak_GetParameter(espeakCAPITALS, 0);
65 wordgap = espeak_GetParameter(espeakWORDGAP, 0);
71 if (priv_n.
getParam(
"voice", voice_num) ==
false) {
74 if (priv_n.
getParam(
"dialect", dialect_num) ==
false) {
75 priv_n.
setParam(
"dialect", dialect_num);
77 if (priv_n.
getParam(
"rate", rate) ==
false) {
80 if (priv_n.
getParam(
"volume", volume) ==
false) {
83 if (priv_n.
getParam(
"pitch", pitch) ==
false) {
86 if (priv_n.
getParam(
"punctuation", punctuation) ==
false) {
87 priv_n.
setParam(
"punctuation", punctuation);
89 if (priv_n.
getParam(
"capitals", capitals) ==
false) {
90 priv_n.
setParam(
"capitals", capitals);
92 if (priv_n.
getParam(
"wordgap", wordgap) ==
false) {
95 priv_n.
param(
"age", age,
int(0));
96 priv_n.
param(
"gender", gender,
int(2));
97 if (age < 0 || age > 100) {
100 if (gender < 0 || gender > 2) {
107 std::memset(&voice_select,0,
sizeof(voice_select));
108 voice_select.name = voice_name.c_str();
109 voice_select.languages = dialect.c_str();
110 voice_select.age = age;
111 voice_select.gender = gender;
118 if (espeak_SetVoiceByProperties(&voice_select) != EE_OK) {
119 ROS_ERROR(
"Could not set espeak voice properties. Aborting.");
125 if (rate < 80 || rate > 450) {
126 ROS_INFO(
"Parameter rate = %d out of range, using default value", rate);
129 if (espeak_SetParameter(espeakRATE, rate, 0) != EE_OK) {
130 ROS_ERROR(
"Could not set espeak rate. Aborting.");
134 if (volume < 0 || volume > 200) {
135 ROS_INFO(
"Parameter volume = %d out of range, using default value", volume);
138 if (espeak_SetParameter(espeakVOLUME, volume, 0) != EE_OK) {
139 ROS_ERROR(
"Could not set espeak volume. Aborting.");
143 if (pitch < 0 || pitch > 100) {
144 ROS_INFO(
"Parameter pitch = %d out of range, using default value", pitch);
147 if (espeak_SetParameter(espeakPITCH, pitch, 0) != EE_OK) {
148 ROS_ERROR(
"Could not set espeak pitch. Aborting.");
152 if (range < 0 || range > 100) {
153 ROS_INFO(
"Parameter range = %d out of range, using default value", range);
156 if (espeak_SetParameter(espeakRANGE, range, 0) != EE_OK) {
157 ROS_ERROR(
"Could not set espeak range. Aborting.");
161 if (punctuation < 0 || punctuation > 2) {
162 ROS_INFO(
"Parameter punctuation out of range, using default value");
165 if (espeak_SetParameter(espeakPUNCTUATION,
166 espeak_PUNCT_TYPE(punctuation), 0) != EE_OK) {
167 ROS_ERROR(
"Could not set espeak punctuation. Aborting.");
171 if (capitals < 0 || capitals > 3) {
172 ROS_INFO(
"Parameter capitals out of range, using default value");
175 if (espeak_SetParameter(espeakCAPITALS, capitals, 0) != EE_OK) {
176 ROS_ERROR(
"Could not set espeak capitals. Aborting.");
180 if (wordgap < 0 || wordgap > 1000 || wordgap % 10 != 0) {
181 ROS_INFO(
"Parameter wordgap out of range, using default value");
184 if (espeak_SetParameter(espeakWORDGAP, wordgap, 0) != EE_OK) {
185 ROS_ERROR(
"Could not set espeak wordgap. Aborting.");
190 dynamic_reconfigure::Server<espeak_ros::EspeakConfig> server;
191 dynamic_reconfigure::Server<espeak_ros::EspeakConfig>::CallbackType
f;
193 server.setCallback(f);
204 boost::mutex::scoped_lock u_lock(
mtx);
206 std::string voice, dialect;
210 espeak_VOICE voice_select;
211 std::memset(&voice_select,0,
sizeof(voice_select));
212 voice_select.name = voice.c_str();
213 voice_select.languages = dialect.c_str();
214 voice_select.age = cfg.age;
215 voice_select.gender = cfg.gender;
217 if (espeak_SetVoiceByProperties(&voice_select) != EE_OK) {
218 ROS_ERROR(
"[espeak_node]: Could not set espeak voice properties. Aborting.");
224 if (espeak_SetParameter(espeakRATE, cfg.rate, 0) != EE_OK) {
225 ROS_ERROR(
"[espeak_node]: Could not set espeak rate. Aborting.");
228 if (espeak_SetParameter(espeakVOLUME, cfg.volume, 0) != EE_OK) {
229 ROS_ERROR(
"[espeak_node]: Could not set espeak volume. Aborting.");
232 if (espeak_SetParameter(espeakPITCH, cfg.pitch, 0) != EE_OK) {
233 ROS_ERROR(
"[espeak_node]: Could not set espeak pitch. Aborting.");
236 if (espeak_SetParameter(espeakRANGE, cfg.range, 0) != EE_OK) {
237 ROS_ERROR(
"[espeak_node]: Could not set espeak range. Aborting.");
240 if (espeak_SetParameter(espeakPUNCTUATION,
241 espeak_PUNCT_TYPE(cfg.punctuation), 0) != EE_OK) {
242 ROS_ERROR(
"[espeak_node]: Could not set espeak punctuation. Aborting.");
245 if (espeak_SetParameter(espeakCAPITALS, cfg.capitals, 0) != EE_OK) {
246 ROS_ERROR(
"[espeak_node]: Could not set espeak capitals. Aborting.");
249 int wordgap = cfg.wordgap % 10;
250 if (espeak_SetParameter(espeakWORDGAP, wordgap, 0) != EE_OK) {
251 ROS_ERROR(
"[espeak_node]: Could not set espeak wordgap. Aborting.");
259 case 0: voice.assign(
"default");
261 case 1: voice.assign(
"english");
263 case 2: voice.assign(
"lancashire");
265 case 3: voice.assign(
"english-rp");
267 case 4: voice.assign(
"english-wmids");
269 case 5: voice.assign(
"english-us");
271 case 6: voice.assign(
"en-scottish");
273 case 7: voice.assign(
"brazil");
275 default: voice.assign(
"english");
283 case 0: dialect.assign(
"en");
285 case 1: dialect.assign(
"en-uk");
287 case 2: dialect.assign(
"en-uk-north");
289 case 3: dialect.assign(
"en-uk-rp");
291 case 4: dialect.assign(
"en-uk-wmids");
293 case 5: dialect.assign(
"en-us");
295 case 6: dialect.assign(
"en-sc");
297 case 7: dialect.assign(
"pt-br");
299 default: dialect.assign(
"en-uk");
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
void espeak_callback(const std_msgs::String::ConstPtr &line)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void dyn_cfg_callback(espeak_ros::EspeakConfig &cfg, uint32_t level)
bool getParam(const std::string &key, std::string &s) const
std::string getDialectName(int d)
std::string getVoiceName(int v)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const