Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <iostream>
00031 #include <sstream>
00032 #include <string>
00033 #include "ros/ros.h"
00034 #include "std_msgs/String.h"
00035 #include "sound_play/SoundRequest.h"
00036 #include <ctype.h>
00037 #include <stdio.h>
00038 #include <curl/curl.h>
00039 #include <jansson.h>
00040 #include <time.h>
00041
00042 using namespace std;
00043
00044 void stringCallback(const std_msgs::String msg);
00045 void createFilename();
00046
00047 ros::Publisher soundPub;
00048
00049
00050 string audioPath;
00051 string jsonPath;
00052 string language;
00053 bool mplayer;
00054
00055 json_t* root;
00056
00057
00058 CURL *curl;
00059 CURLcode res;
00060 char filename[51];
00061
00062 int main(int argc, char** argv) {
00063
00064
00065 ros::init(argc, argv, "speech_database");
00066 ros::NodeHandle n("~");
00067 ros::spinOnce();
00068 ros::Subscriber sub;
00069 sub = n.subscribe("/speech", 10, stringCallback);
00070 soundPub = n.advertise<sound_play::SoundRequest>("/robotsound", 10);
00071
00072 ros::Rate loop_rate(10);
00073 if(!n.getParam("audioPath", audioPath)) {
00074 ROS_ERROR("Parameter audioPath not found");
00075 ros::shutdown();
00076 }
00077
00078 if(audioPath.find_last_of("/") != audioPath.length()-1) {
00079 audioPath.append("/");
00080 }
00081 if(!n.getParam("language", language)) {
00082 ROS_ERROR("Parameter language not found");
00083 ros::shutdown();
00084 }
00085 if(!n.getParam("jsonPath", jsonPath)) {
00086 ROS_ERROR("Parameter jsonPath not found");
00087 ros::shutdown();
00088 }
00089 if(!n.getParam("mplayer", mplayer)) {
00090 ROS_ERROR("Parameter mplayer not found");
00091 ros::shutdown();
00092 }
00093
00094
00095 srand(time(NULL));
00096 srand(time(NULL) + rand());
00097
00098
00099 json_error_t err;
00100 root = json_load_file(jsonPath.c_str(), 0, &err);
00101 if(!root) {
00102 ROS_DEBUG("json file %s does not exist, a new file will be created", jsonPath.c_str());
00103 root = json_object();
00104 } else {
00105 ROS_DEBUG("json file %s successfully opened", jsonPath.c_str());
00106 }
00107
00108
00109 curl = curl_easy_init();
00110
00111 while (curl && ros::ok()) {
00112 ros::spinOnce();
00113 loop_rate.sleep();
00114 }
00115
00116 curl_easy_cleanup(curl);
00117
00118 return 0;
00119 }
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135 void stringCallback(const std_msgs::String msg) {
00136 string data = msg.data;
00137 if(data.length() > 100) {
00138 ROS_WARN("The exceeds the maximum length of 100 characters and will not be synthesised.");
00139 return;
00140 }
00141
00142
00143 for(int i = 0; i < data.length(); i++) {
00144 data[i] = (char) tolower((int) data[i]);
00145 }
00146
00147
00148 json_t* entry = json_object_get(root, data.c_str());
00149 if(!entry) {
00150 ROS_DEBUG("Entry does not exist, downloading new file");
00151
00152
00153 stringstream urlStream;
00154 urlStream << "http://translate.google.com/translate_tts?tl=";
00155 urlStream << language << "&q=";
00156 char* str = curl_easy_escape(curl, data.c_str(), 0);
00157 urlStream << str;
00158 curl_free(str);
00159
00160 stringstream filenameStream;
00161 FILE* file = fopen("/dev/null", "r");
00162 while(file) {
00163 curl_easy_setopt(curl, CURLOPT_URL, urlStream.str().c_str());
00164 filenameStream.str("");
00165 filenameStream.clear();
00166 filenameStream << audioPath;
00167 createFilename();
00168 filenameStream << filename;
00169 file = fopen(filenameStream.str().c_str(), "r");
00170 }
00171
00172 file = fopen(filenameStream.str().c_str(), "w");
00173 if(!file) {
00174 ROS_ERROR("Could not open file %s", filenameStream.str().c_str());
00175 fclose(file);
00176 return;
00177 }
00178
00179 curl_easy_setopt(curl, CURLOPT_WRITEDATA, file) ;
00180 res = curl_easy_perform(curl);
00181 fclose(file);
00182
00183
00184 if(res == CURLE_OK) {
00185 ROS_DEBUG("File downloaded and stored in %s", filenameStream.str().c_str());
00186 } else {
00187 ROS_ERROR("Download failed, curl_easy_perform() error: %s", curl_easy_strerror(res));
00188 return;
00189 }
00190
00191
00192 entry = json_string(filename);
00193 json_object_set(root, data.c_str(), entry);
00194
00195 if(json_dump_file(root, jsonPath.c_str(), 0) == 0) {
00196 ROS_DEBUG("json file successfully written to %s", jsonPath.c_str());
00197 } else {
00198 ROS_ERROR("json file could not be written, all changes are lost");
00199 }
00200 }
00201
00202
00203 sound_play::SoundRequest req;
00204 req.sound = req.ALL;
00205 req.command = req.PLAY_STOP;
00206 if(!mplayer) {
00207 soundPub.publish(req);
00208 }
00209
00210
00211 req.sound = req.PLAY_FILE;
00212 req.command = req.PLAY_ONCE;
00213 string path_to_file = audioPath;
00214 path_to_file.append(json_string_value(entry));
00215 req.arg = path_to_file;
00216
00217 if(mplayer) {
00218 string cmd_str = "mplayer ";
00219 cmd_str = cmd_str + path_to_file;
00220 system(cmd_str.c_str());
00221 } else {
00222 soundPub.publish(req);
00223 }
00224 }
00225
00226
00227
00228
00229
00230
00231
00232 void createFilename() {
00233 int i;
00234 char ch;
00235 for(i = 0; i < 50; i++) {
00236 int ran = rand() % 62;
00237 ch = (char) ran;
00238 if(ch < 10) {
00239 ch = (char) ch + '0';
00240 } else if(ch < 36) {
00241 ch = (ch - 10) + 'A';
00242 } else {
00243 ch = (ch - 36) + 'a';
00244 }
00245 filename[i] = ch;
00246 }
00247 filename[50] = 0;
00248 }