talosaudio.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 ## Author: Devon Ash
00004 ## Maintainer: noobaca2@gmail.com
00005 ############################### IMPORTS ############################
00006 
00007 
00008 import roslib
00009 import rospy
00010 import pyttsx
00011 
00012 from talos_audio.srv import ListenFor
00013 from talos_audio.srv import ListenForAll
00014 from talos_audio.srv import ListenForAll
00015 from std_msgs.msg import String
00016 from std_srvs.srv import Empty, EmptyRequest
00017 from sound_play.libsoundplay import SoundClient
00018 
00019 ########################### DEVELOEPR README #######################
00020 
00021 # 1. The speech listener class works ontop of the recognizer.py from
00022 # pocketsphinx package for ros.
00023 
00024 # 2. Its intended use is the .listenFor()
00025 # function which will return false until the callback from
00026 # pocketsphinx returns the matched string. 
00027 
00028 # 3.This is useful instead of putting a subscripter 
00029 # in every state/class/ for the smach state machine
00030 
00031 class TalosAudio:
00032 
00033     def __init__(self):
00034         self.engine = pyttsx.init()
00035         self.old_word = "No words heard"
00036         self.heard_word = False
00037         self.listening = False
00038         self.words_listened_for = []
00039         self.last_word_heard = "No words heard"
00040         self.listen_for_any = False
00041 
00042     def listen_for_words_callback(self, data):
00043         rospy.loginfo(rospy.get_name() + ": I heard %s", data.data)
00044         self.old_word = data.data
00045 
00046         if data.data in self.words_listened_for:
00047             self.heard_word = True
00048             rospy.loginfo(rospy.get_name() + ": Word '%s' has been heard", data.data)
00049             self.last_word_heard = data.data
00050             self.stop_listening()
00051         elif self.listen_for_any:
00052             self.last_word_heard = data.data
00053             self.stop_listening()
00054 
00055     def listen_for_all(self, request):
00056         if not self.listening and not self.heard_word:
00057             self.words_listened_for = request.words
00058             self.start_listening()
00059             rospy.loginfo("Listening for an array of phrases")
00060         else:
00061             if (self.heard_word):
00062                 self.words_listened_for = []
00063                 self.heard_word = False
00064                 self.listening = False
00065                 return self.last_word_heard
00066             
00067         return "NoCommandDetected"
00068 
00069     def stop_listening(self):
00070         try:
00071                 # Once the words have been heard, no need to continue listening, shut down the listening. 
00072             stop = rospy.ServiceProxy('recognizer/stop', Empty)
00073             response = stop()
00074         except rospy.ServiceException, e:
00075             print "Service call failed %s" %e
00076             
00077         self.listening = False
00078 
00079     # Tells recognizer/output to start producing values it hears
00080     def start_listening(self):
00081         try:
00082             # Start listening to the recognizer callbacks
00083             start = rospy.ServiceProxy('recognizer/start', Empty)
00084             response = start()
00085         except rospy.ServiceException, e:
00086             print "Service call failed %s" %e
00087 
00088         # At the end of the function, because if the service call fails
00089         # it is not good to have this set to true
00090         self.heard_words = False
00091         self.listening = True
00092 
00093     @staticmethod
00094     def start_recognizer():
00095         try:
00096             # Start listening to the recognizer callbacks
00097             start = rospy.ServiceProxy('recognizer/start', Empty)
00098             response = start()
00099         except rospy.ServiceException, e:
00100             print "Service call failed %s" %e
00101 
00102     @staticmethod
00103     def stop_recognizer():
00104         try:
00105             # Start listening to the recognizer callbacks
00106             start = rospy.ServiceProxy('recognizer/stop', Empty)
00107             response = start()
00108         except rospy.ServiceException, e:
00109             print "Service call failed %s" %e
00110  
00111     def say(self, utterance):
00112         self.engine.say(utterance)
00113         self.engine.runAndWait()
00114 
00115 def main():
00116 
00117     listener = TalosAudio()
00118     rospy.init_node("speech_listener")
00119     rospy.loginfo(rospy.get_name() + ": Started speech listener")
00120     rospy.Subscriber("recognizer/output", String, listener.listen_for_words_callback)
00121     listen_for_all_service = rospy.Service('listen_for_all', ListenForAll, listener.listen_for_all)
00122    
00123     say_service = rospy.Service('say', ListenFor, listener.say)
00124 
00125     try:
00126         # On startup, do not listen for anything
00127         listener.stop_listening()
00128         rospy.loginfo("Stopping recognizer/output service. This node will activate it again when asked to listen for something.")
00129     except rospy.ServiceException, e:
00130         print "Service call failed %s" %e
00131         
00132     rospy.spin()
00133     
00134 if __name__ == "__main__":
00135     main()


talos_audio
Author(s):
autogenerated on Sat Jun 8 2019 20:11:45