Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015 package edu.tum.cs.ias.knowrob.mod_dialog;
00016
00017 import edu.cmu.sphinx.jsapi.JSGFGrammar;
00018 import edu.cmu.sphinx.recognizer.Recognizer;
00019 import edu.cmu.sphinx.frontend.util.Microphone;
00020 import edu.cmu.sphinx.result.Result;
00021 import edu.cmu.sphinx.util.props.ConfigurationManager;
00022 import edu.cmu.sphinx.util.props.PropertyException;
00023
00024 import java.io.IOException;
00025 import java.net.URL;
00026 import javax.speech.recognition.GrammarException;
00027 import javax.speech.recognition.RuleGrammar;
00028 import javax.speech.recognition.RuleParse;
00029
00030 import ros.NodeHandle;
00031 import ros.Publisher;
00032 import ros.Ros;
00033 import ros.RosException;
00034
00035
00036
00044 public class SpeechRecognitionNode {
00045 private Recognizer recognizer;
00046 private JSGFGrammar jsgfGrammarManager;
00047 private Microphone microphone;
00048
00050
00051
00052 static Boolean rosInitialized = false;
00053 static Ros ros;
00054 static NodeHandle n;
00055 static Publisher<ros.pkg.std_msgs.msg.String> pub;
00056
00065 public SpeechRecognitionNode() throws
00066 IOException, PropertyException, InstantiationException {
00067
00068 URL url = SpeechRecognitionNode.class.getResource("jsgf.config.xml");
00069 ConfigurationManager cm = new ConfigurationManager(url);
00070
00071
00072
00073
00074 recognizer = (Recognizer) cm.lookup("recognizer");
00075 jsgfGrammarManager = (JSGFGrammar) cm.lookup("jsgfGrammar");
00076 microphone = (Microphone) cm.lookup("microphone");
00077
00078
00079
00080 try {
00081 initRos();
00082 pub = n.advertise("/knowrob/speech_in", new ros.pkg.std_msgs.msg.String(), 100);
00083
00084 } catch (RosException e) {
00085 e.printStackTrace();
00086 }
00087
00088 }
00089
00090
00094 public void execute() throws IOException, GrammarException {
00095 System.out.println("JSGF Demo Version 1.0\n");
00096
00097 System.out.print(" Loading recognizer ...");
00098 recognizer.allocate();
00099 System.out.println(" Ready");
00100
00101 if (microphone.startRecording()) {
00102 loadAndRecognize("queries");
00103 } else {
00104 System.out.println("Can't start the microphone");
00105 }
00106
00107 System.out.print("\nDone. Cleaning up ...");
00108 recognizer.deallocate();
00109
00110 System.out.println(" Goodbye.\n");
00111 System.exit(0);
00112 }
00113
00114
00115
00119 protected static void initRos() {
00120
00121 ros = Ros.getInstance();
00122
00123 if(!Ros.getInstance().isInitialized()) {
00124 ros.init("knowrob_sphinx");
00125 }
00126 n = ros.createNodeHandle();
00127
00128 }
00129
00140 private void loadAndRecognize(String grammarName) throws
00141 IOException, GrammarException {
00142 jsgfGrammarManager.loadJSGF(grammarName);
00143 recognizeAndReport();
00144 }
00145
00154 private void recognizeAndReport() throws GrammarException {
00155 boolean done = false;
00156
00157
00158 while (!done) {
00159 Result result = recognizer.recognize();
00160 String bestResult = result.getBestFinalResultNoFiller();
00161 RuleGrammar ruleGrammar = jsgfGrammarManager.getRuleGrammar();
00162 RuleParse ruleParse = ruleGrammar.parse(bestResult, null);
00163 if (ruleParse != null) {
00164 System.out.println("\n " + sphinxToKnowrob(bestResult) + "\n");
00165
00166
00167 ros.pkg.std_msgs.msg.String m = new ros.pkg.std_msgs.msg.String();
00168 m.data = sphinxToKnowrob(bestResult);
00169 pub.publish(m);
00170
00171 done = isExit(ruleParse);
00172 }
00173 }
00174 }
00175
00181 String sphinxToKnowrob(String q) {
00182
00183 q=q.replaceAll(" one", "1");
00184 q=q.replaceAll(" two", "2");
00185 q=q.replaceAll(" three", "3");
00186 q=q.replaceAll(" four", "4");
00187 q=q.replaceAll(" five", "5");
00188 q=q.replaceAll(" six", "6");
00189 q=q.replaceAll(" seven", "7");
00190 q=q.replaceAll(" eight", "8");
00191 q=q.replaceAll(" nine", "9");
00192 q=q.replaceAll(" zero", "0");
00193
00194 return q + "?";
00195 }
00196
00202 private boolean isExit(RuleParse ruleParse) {
00203 String[] tags = ruleParse.getTags();
00204
00205 for (int i = 0; tags != null && i < tags.length; i++) {
00206 if (tags[i].trim().equals("exit")) {
00207 return true;
00208 }
00209 }
00210 return false;
00211 }
00212
00213
00218 public static void main(String[] args) {
00219 try {
00220 SpeechRecognitionNode SpeechRecognitionNode = new SpeechRecognitionNode();
00221 SpeechRecognitionNode.execute();
00222 } catch (IOException ioe) {
00223 System.out.println("I/O Error " + ioe);
00224 } catch (PropertyException e) {
00225 System.out.println("Problem configuring recognizer" + e);
00226 } catch (InstantiationException e) {
00227 System.out.println("Problem creating components " + e);
00228 } catch (GrammarException e) {
00229 System.out.println("Problem with Grammar " + e);
00230 }
00231 }
00232 }