$search
00001 package edu.tum.cs.ias.mary_tts; 00002 00037 import java.io.ByteArrayInputStream; 00038 import java.io.ByteArrayOutputStream; 00039 import java.io.IOException; 00040 00041 import javax.sound.sampled.AudioInputStream; 00042 import javax.sound.sampled.AudioSystem; 00043 import javax.sound.sampled.LineEvent; 00044 import javax.sound.sampled.LineListener; 00045 import javax.sound.sampled.UnsupportedAudioFileException; 00046 00047 import marytts.util.data.audio.AudioPlayer; 00048 import marytts.client.MaryClient; 00049 import marytts.client.http.Address; 00050 00051 import ros.NodeHandle; 00052 import ros.Publisher; 00053 import ros.Ros; 00054 import ros.RosException; 00055 import ros.ServiceServer; 00056 import ros.Subscriber; 00057 import ros.pkg.mary_tts.srv.*; 00058 00059 00067 public class MaryROSClient { 00068 00069 static MaryClient mary; 00070 static LineListener lineListener; 00071 static ByteArrayOutputStream baos; 00072 static AudioInputStream ais; 00073 00074 static Ros ros; 00075 static NodeHandle n; 00076 static Subscriber.QueueingCallback<ros.pkg.std_msgs.msg.String> callback; 00077 00078 static String voice = "dfki-obadiah"; 00079 00080 protected static void initRos() { 00081 00082 ros = Ros.getInstance(); 00083 00084 if(!Ros.getInstance().isInitialized()) { 00085 ros.init("mary_text_to_speech"); 00086 } 00087 n = ros.createNodeHandle(); 00088 callback = new Subscriber.QueueingCallback<ros.pkg.std_msgs.msg.String>(); 00089 } 00090 00091 public MaryROSClient() { 00092 00093 try { 00094 init_mary(); 00095 } catch (IOException e) { 00096 e.printStackTrace(); 00097 } 00098 00099 // start ROS environment 00100 initRos(); 00101 00102 Thread speechIn = new Thread( new SpeechOutListenerThread() ); 00103 speechIn.start(); 00104 00105 Thread answerQueries = new Thread( new AnswerQueriesThread() ); 00106 answerQueries.start(); 00107 00108 Thread startRosServices = new Thread( new RosServiceThread() ); 00109 startRosServices.start(); 00110 00111 } 00112 00113 00114 00115 protected void init_mary() throws IOException { 00116 00117 String serverHost = System.getProperty("server.host", "localhost"); 00118 int serverPort = Integer.getInteger("server.port", 59125).intValue(); 00119 00120 boolean initialized=false; 00121 00122 while(!initialized) { 00123 try{ 00124 Thread.sleep(1000); 00125 mary = MaryClient.getMaryClient(new Address(serverHost, serverPort)); 00126 initialized=true; 00127 } catch(IOException e) { } 00128 catch (InterruptedException e) { } 00129 } 00130 00131 00132 lineListener = new LineListener() { 00133 public void update(LineEvent event) { 00134 if (event.getType() == LineEvent.Type.START) { 00135 System.err.println("Audio started playing."); 00136 } else if (event.getType() == LineEvent.Type.STOP) { 00137 System.err.println("Audio stopped playing."); 00138 } else if (event.getType() == LineEvent.Type.OPEN) { 00139 System.err.println("Audio line opened."); 00140 } else if (event.getType() == LineEvent.Type.CLOSE) { 00141 System.err.println("Audio line closed."); 00142 } 00143 } 00144 }; 00145 } 00146 00147 public static class SpeechOutListenerThread implements Runnable { 00148 00149 @Override public void run() { 00150 00151 try { 00152 00153 n.advertise("/mary/tts", new ros.pkg.std_msgs.msg.String(), 100); 00154 Subscriber<ros.pkg.std_msgs.msg.String> sub = n.subscribe("/mary/tts", new ros.pkg.std_msgs.msg.String(), callback, 10); 00155 00156 n.spin(); 00157 sub.shutdown(); 00158 00159 } catch(RosException e) { 00160 e.printStackTrace(); 00161 } 00162 } 00163 } 00164 00165 00166 00167 public static class AnswerQueriesThread implements Runnable { 00168 00169 00170 public AnswerQueriesThread() { 00171 00172 } 00173 00174 @Override public void run() { 00175 00176 try { 00177 00178 ros.pkg.std_msgs.msg.String res; 00179 while (n.isValid()) { 00180 00181 res = callback.pop(); 00182 00183 try{ 00184 00185 baos = new ByteArrayOutputStream(); 00186 mary.process(res.data, "TEXT", "AUDIO", "en_GB", "WAVE", voice, baos); 00187 ais = AudioSystem.getAudioInputStream(new ByteArrayInputStream(baos.toByteArray())); 00188 AudioPlayer ap = new AudioPlayer(ais, lineListener); 00189 ap.start(); 00190 00191 } catch (IOException e) { 00192 e.printStackTrace(); 00193 } catch (UnsupportedAudioFileException e) { 00194 e.printStackTrace(); 00195 } 00196 } 00197 00198 } catch (InterruptedException e) { 00199 e.printStackTrace(); 00200 } 00201 } 00202 } 00203 00204 00205 public class RosServiceThread implements Runnable { 00206 00207 @Override public void run() { 00208 00209 try { 00210 n.advertiseService("/mary_tts/set_voice", new SetMaryVoice(), new SetVoiceCallback()); 00211 ros.spin(); 00212 00213 } catch(RosException e) { 00214 e.printStackTrace(); 00215 } 00216 } 00217 } 00218 00226 class SetVoiceCallback implements ServiceServer.Callback<SetMaryVoice.Request, SetMaryVoice.Response> { 00227 00228 @Override 00229 public SetMaryVoice.Response call(SetMaryVoice.Request req) { 00230 00231 SetMaryVoice.Response res = new SetMaryVoice.Response(); 00232 res.result=false; 00233 00234 if (req.voice_name != null && req.voice_name.length() > 0) { 00235 voice = req.voice_name; 00236 res.result=true; 00237 } 00238 00239 return res; 00240 } 00241 } 00242 00243 00244 public static void main(String[] args) { 00245 new MaryROSClient(); 00246 } 00247 }