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     ~mic_name - set the pulsesrc device name for the microphone input.
00009                 e.g. a Logitech G35 Headset has the following device name: alsa_input.usb-Logitech_Logitech_G35_Headset-00-Headset_1.analog-mono
00010                 To list audio device info on your machine, in a terminal type: pacmd list-sources
00011   publications:
00012     ~output (std_msgs/String) - text output
00013   services:
00014     ~start (std_srvs/Empty) - start speech recognition
00015     ~stop (std_srvs/Empty) - stop speech recognition
00016 """
00017 
00018 import roslib; roslib.load_manifest('pocketsphinx')
00019 import rospy
00020 
00021 import pygtk
00022 pygtk.require('2.0')
00023 import gtk
00024 
00025 import gobject
00026 import pygst
00027 pygst.require('0.10')
00028 gobject.threads_init()
00029 import gst
00030 
00031 from std_msgs.msg import String
00032 from std_srvs.srv import *
00033 import os
00034 import commands
00035 
00036 class recognizer(object):
00037     """ GStreamer based speech recognizer. """
00038 
00039     def __init__(self):
00040         # Start node
00041         rospy.init_node("recognizer")
00042 
00043         self._device_name_param = "~mic_name"  # Find the name of your microphone by typing pacmd list-sources in the terminal
00044         self._lm_param = "~lm"
00045         self._dic_param = "~dict"
00046 
00047         # Configure mics with gstreamer launch config
00048         if rospy.has_param(self._device_name_param):
00049             self.device_name = rospy.get_param(self._device_name_param)
00050             self.device_index = self.pulse_index_from_name(self.device_name)
00051             self.launch_config = "pulsesrc device=" + str(self.device_index)
00052             rospy.loginfo("Using: pulsesrc device=%s name=%s", self.device_index, self.device_name)
00053         elif rospy.has_param('~source'):
00054             # common sources: 'alsasrc'
00055             self.launch_config = rospy.get_param('~source')
00056         else:
00057             self.launch_config = 'gconfaudiosrc'
00058 
00059         rospy.loginfo("Launch config: %s", self.launch_config)
00060 
00061         self.launch_config += " ! audioconvert ! audioresample " \
00062                             + '! vader name=vad auto-threshold=true ' \
00063                             + '! pocketsphinx name=asr ! fakesink'
00064 
00065         # Configure ROS settings
00066         self.started = False
00067         rospy.on_shutdown(self.shutdown)
00068         self.pub = rospy.Publisher('~output', String)
00069         rospy.Service("~start", Empty, self.start)
00070         rospy.Service("~stop", Empty, self.stop)
00071 
00072         if rospy.has_param(self._lm_param) and rospy.has_param(self._dic_param):
00073             self.start_recognizer()
00074         else:
00075             rospy.logwarn("lm and dic parameters need to be set to start recognizer.")
00076 
00077     def start_recognizer(self):
00078         rospy.loginfo("Starting recognizer... ")
00079 
00080         self.pipeline = gst.parse_launch(self.launch_config)
00081         self.asr = self.pipeline.get_by_name('asr')
00082         self.asr.connect('partial_result', self.asr_partial_result)
00083         self.asr.connect('result', self.asr_result)
00084         self.asr.set_property('configured', True)
00085         self.asr.set_property('dsratio', 1)
00086 
00087         # Configure language model
00088         if rospy.has_param(self._lm_param):
00089             lm = rospy.get_param(self._lm_param)
00090         else:
00091             rospy.logerr('Recognizer not started. Please specify a language model file.')
00092             return
00093 
00094         if rospy.has_param(self._dic_param):
00095             dic = rospy.get_param(self._dic_param)
00096         else:
00097             rospy.logerr('Recognizer not started. Please specify a dictionary.')
00098             return
00099 
00100         self.asr.set_property('lm', lm)
00101         self.asr.set_property('dict', dic)
00102 
00103         self.bus = self.pipeline.get_bus()
00104         self.bus.add_signal_watch()
00105         self.bus_id = self.bus.connect('message::application', self.application_message)
00106         self.pipeline.set_state(gst.STATE_PLAYING)
00107         self.started = True
00108 
00109     def pulse_index_from_name(self, name):
00110         output = commands.getstatusoutput("pacmd list-sources | grep -B 1 'name: <" + name + ">' | grep -o -P '(?<=index: )[0-9]*'")
00111 
00112         if len(output) == 2:
00113             return output[1]
00114         else:
00115             raise Exception("Error. pulse index doesn't exist for name: " + name)
00116 
00117     def stop_recognizer(self):
00118         if self.started:
00119             self.pipeline.set_state(gst.STATE_NULL)
00120             self.pipeline.remove(self.asr)
00121             self.bus.disconnect(self.bus_id)
00122             self.started = False
00123 
00124     def shutdown(self):
00125         """ Delete any remaining parameters so they don't affect next launch """
00126         for param in [self._device_name_param, self._lm_param, self._dic_param]:
00127             if rospy.has_param(param):
00128                 rospy.delete_param(param)
00129 
00130         """ Shutdown the GTK thread. """
00131         gtk.main_quit()
00132 
00133     def start(self, req):
00134         self.start_recognizer()
00135         rospy.loginfo("recognizer started")
00136         return EmptyResponse()
00137 
00138     def stop(self, req):
00139         self.stop_recognizer()
00140         rospy.loginfo("recognizer stopped")
00141         return EmptyResponse()
00142 
00143     def asr_partial_result(self, asr, text, uttid):
00144         """ Forward partial result signals on the bus to the main thread. """
00145         struct = gst.Structure('partial_result')
00146         struct.set_value('hyp', text)
00147         struct.set_value('uttid', uttid)
00148         asr.post_message(gst.message_new_application(asr, struct))
00149 
00150     def asr_result(self, asr, text, uttid):
00151         """ Forward result signals on the bus to the main thread. """
00152         struct = gst.Structure('result')
00153         struct.set_value('hyp', text)
00154         struct.set_value('uttid', uttid)
00155         asr.post_message(gst.message_new_application(asr, struct))
00156 
00157     def application_message(self, bus, msg):
00158         """ Receive application messages from the bus. """
00159         msgtype = msg.structure.get_name()
00160         if msgtype == 'partial_result':
00161             self.partial_result(msg.structure['hyp'], msg.structure['uttid'])
00162         if msgtype == 'result':
00163             self.final_result(msg.structure['hyp'], msg.structure['uttid'])
00164 
00165     def partial_result(self, hyp, uttid):
00166         """ Delete any previous selection, insert text and select it. """
00167         rospy.logdebug("Partial: " + hyp)
00168 
00169     def final_result(self, hyp, uttid):
00170         """ Insert the final result. """
00171         msg = String()
00172         msg.data = str(hyp.lower())
00173         rospy.loginfo(msg.data)
00174         self.pub.publish(msg)
00175 
00176 if __name__ == "__main__":
00177     start = recognizer()
00178     gtk.main()
00179 


pocketsphinx
Author(s): Michael Ferguson
autogenerated on Thu Jun 6 2019 21:43:56