recognizer.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 """
00004 recognizer.py is a wrapper for pocketsphinx.
00005   parameters:
00006     ~lm - filename of language model
00007     ~dict - filename of dictionary
00008   publications:
00009     ~output (std_msgs/String) - text output
00010   services:
00011     ~start (std_srvs/Empty) - start speech recognition
00012     ~stop (std_srvs/Empty) - stop speech recognition
00013 """
00014 
00015 import roslib; roslib.load_manifest('pocketsphinx')
00016 import rospy
00017 
00018 import pygtk
00019 pygtk.require('2.0')
00020 import gtk
00021 
00022 import gobject
00023 import pygst
00024 pygst.require('0.10')
00025 gobject.threads_init()
00026 import gst
00027 
00028 from std_msgs.msg import String
00029 from std_srvs.srv import *
00030 
00031 class recognizer(object):
00032     """ GStreamer based speech recognizer. """
00033 
00034     def __init__(self):
00035         """ Initialize the speech pipeline components. """
00036         rospy.init_node('recognizer')
00037         self.pub = rospy.Publisher('~output',String)
00038         rospy.on_shutdown(self.shutdown)
00039 
00040         # services to start/stop recognition
00041         rospy.Service("~start", Empty, self.start)
00042         rospy.Service("~stop", Empty, self.stop)
00043 
00044         # configure pipeline
00045         self.pipeline = gst.parse_launch('gconfaudiosrc ! audioconvert ! audioresample '
00046                                          + '! vader name=vad auto-threshold=true '
00047                                          + '! pocketsphinx name=asr ! fakesink')
00048         asr = self.pipeline.get_by_name('asr')
00049         asr.connect('partial_result', self.asr_partial_result)
00050         asr.connect('result', self.asr_result)
00051         asr.set_property('configured', True)
00052         asr.set_property('dsratio', 1)
00053 
00054         # parameters for lm and dic
00055         try:
00056             lm_ = rospy.get_param('~lm')
00057             asr.set_property('lm', lm_)
00058         except:
00059             try:
00060                 fsg_ = rospy.get_param('~fsg')
00061                 asr.set_property('fsg', fsg_)
00062             except:
00063                 rospy.logerr('Please specify a language model file or a fsg grammar file')
00064                 return
00065         try:
00066             dict_ = rospy.get_param('~dict')
00067         except:
00068             rospy.logerr('Please specify a dictionary')
00069             return
00070 
00071         asr.set_property('dict', dict_)
00072         bus = self.pipeline.get_bus()
00073         bus.add_signal_watch()
00074         bus.connect('message::application', self.application_message)
00075         self.start(None)
00076         gtk.main()
00077         
00078     def shutdown(self):
00079         """ Shutdown the GTK thread. """
00080         gtk.main_quit()
00081 
00082     def start(self, req):
00083         self.pipeline.set_state(gst.STATE_PLAYING)
00084         return EmptyResponse()
00085 
00086     def stop(self, req):
00087         self.pipeline.set_state(gst.STATE_PAUSED)
00088         #vader = self.pipeline.get_by_name('vad')
00089         #vader.set_property('silent', True)
00090         return EmptyResponse()
00091 
00092     def asr_partial_result(self, asr, text, uttid):
00093         """ Forward partial result signals on the bus to the main thread. """
00094         struct = gst.Structure('partial_result')
00095         struct.set_value('hyp', text)
00096         struct.set_value('uttid', uttid)
00097         asr.post_message(gst.message_new_application(asr, struct))
00098 
00099     def asr_result(self, asr, text, uttid):
00100         """ Forward result signals on the bus to the main thread. """
00101         struct = gst.Structure('result')
00102         struct.set_value('hyp', text)
00103         struct.set_value('uttid', uttid)
00104         asr.post_message(gst.message_new_application(asr, struct))
00105 
00106     def application_message(self, bus, msg):
00107         """ Receive application messages from the bus. """
00108         msgtype = msg.structure.get_name()
00109         if msgtype == 'partial_result':
00110             self.partial_result(msg.structure['hyp'], msg.structure['uttid'])
00111         if msgtype == 'result':
00112             self.final_result(msg.structure['hyp'], msg.structure['uttid'])
00113 
00114     def partial_result(self, hyp, uttid):
00115         """ Delete any previous selection, insert text and select it. """
00116         print "Partial: " + hyp
00117 
00118     def final_result(self, hyp, uttid):
00119         """ Insert the final result. """
00120         msg = String()
00121         msg.data = str(hyp.lower())
00122         rospy.loginfo(msg.data)
00123         self.pub.publish(msg)
00124 
00125 if __name__=="__main__":
00126     r = recognizer()
00127 


pocketsphinx
Author(s): Michael Ferguson
autogenerated on Mon Oct 6 2014 03:27:36