$search
00001 #!/usr/bin/env python 00002 00003 """ 00004 talkback.py - Say back what is heard by the pocketsphinx recognizer. 00005 """ 00006 00007 import roslib; roslib.load_manifest('pi_speech_tutorial') 00008 import rospy 00009 from std_msgs.msg import String 00010 00011 from sound_play.libsoundplay import SoundClient 00012 00013 class TalkBack: 00014 def __init__(self): 00015 rospy.on_shutdown(self.cleanup) 00016 00017 self.voice = rospy.get_param("~voice", "voice_don_diphone") 00018 self.wavepath = rospy.get_param("~wavepath", "") 00019 00020 # Create the sound client object 00021 self.soundhandle = SoundClient() 00022 00023 rospy.sleep(1) 00024 self.soundhandle.stopAll() 00025 00026 # Announce that we are ready for input 00027 self.soundhandle.playWave(self.wavepath + "/R2D2a.wav") 00028 rospy.sleep(1) 00029 self.soundhandle.say("Ready", self.voice) 00030 00031 rospy.loginfo("Say one of the navigation commands...") 00032 00033 # Subscribe to the recognizer output 00034 rospy.Subscriber('/recognizer/output', String, self.talkback) 00035 00036 def talkback(self, msg): 00037 # Print the recognized words on the screen 00038 rospy.loginfo(msg.data) 00039 00040 # Speak the recognized words in the selected voice 00041 self.soundhandle.say(msg.data, self.voice) 00042 00043 # Uncomment to play one of the built-in sounds 00044 #rospy.sleep(2) 00045 #self.soundhandle.play(5) 00046 00047 # Uncomment to play a wave file 00048 #rospy.sleep(2) 00049 #self.soundhandle.playWave(self.wavepath + "/R2D2a.wav") 00050 00051 def cleanup(self): 00052 rospy.loginfo("Shutting down talkback node...") 00053 00054 if __name__=="__main__": 00055 rospy.init_node('talkback') 00056 try: 00057 TalkBack() 00058 rospy.spin() 00059 except: 00060 pass 00061