gspeech_node.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 
00004 PACKAGE='alfred_sr_linux'
00005 NODE='system_speech'
00006 
00007 PUB_SPEECH = 'speech'
00008 PUB_CONFIDENCE = 'confidence'
00009 
00010 import roslib; 
00011 roslib.load_manifest( PACKAGE )
00012 roslib.load_manifest( 'media_msgs' )
00013 import shlex,subprocess,os,sys
00014 import rospy
00015 
00016 from media_msgs.msg import *
00017 from std_msgs.msg import Int8
00018 
00019 lang = 'fr-FR'
00020 cmd1 = 'sox -r 16000 -t alsa default /tmp/recording.flac silence 1 0.3 1% 1 2.0 1%'
00021 #cmd1='sox -r 16000 -t alsa hw:1,0 /tmp/recording.flac silence 1 0.2 5% 1 1.0 5%'
00022 cmd2='wget -q -U "Mozilla/5.0" --remote-encoding=utf-8 --post-file /tmp/recording.flac --header="Content-Type: audio/x-flac; rate=16000" -O - "http://www.google.com/speech-api/v1/recognize?client=chromium&lang=fr-FR"' # % (lang, ) # 
00023 
00024 class SpeechNode( object ):
00025     """ """
00026     
00027     def __init__(self):
00028         rospy.init_node(NODE)
00029         pubs = rospy.Publisher( PUB_SPEECH, Command )
00030         pubc = rospy.Publisher(PUB_CONFIDENCE, Int8)
00031         
00032         args2 = shlex.split(cmd2)
00033         while not rospy.is_shutdown():
00034             os.system(cmd1)     
00035             output,error = subprocess.Popen(args2,stdout = subprocess.PIPE, stderr= subprocess.PIPE).communicate()
00036         
00037         rospy.loginfo( error )
00038         rospy.loginfo( output )
00039         
00040         if str( error ) == "Aborted.":
00041             sys.exit( 1 )
00042         
00043         if not error and len( output ) > 16:
00044             a = eval( output )
00045             rospy.loginfo( a )
00046             hypotheses = a['hypotheses']
00047             
00048             if hypotheses and len( hypotheses ) > 0:
00049                 hypothese = hypotheses[0]
00050                 confidence = float( hypothese['confidence'] )
00051                 
00052                 if confidence:
00053                     confidence = int( confidence * 100 )
00054                 
00055                 data = ( hypothese['utterance'] )
00056                 rospy.loginfo( data )
00057                 if data and data != "":
00058                     rospy.logdebug( "%s %s", str( data ), confidence )
00059                     
00060                     command = Command()
00061                     command.context = Context()
00062                     command.context.where = "/home/salon/"
00063                     command.context.who = "Mickael"
00064                     command.action = "say"
00065                     command.subject = data
00066                     
00067                     pubs.publish( command )
00068                     pubc.publish( confidence )
00069                     
00070                     if data == "arrêt du système":
00071                         sys.exit( 0 )
00072         
00073 def run():
00074     try:
00075         SpeechNode()
00076     except rospy.ROSInterruptException, e:
00077         sys.exit(1) 
00078         pass
00079     #except KeyboardInterrupt:
00080     #    sys.exit(1)
00081 
00082 if __name__ == '__main__':
00083     run()
00084 


alfred_sr_linux
Author(s): Mickael Gaillard
autogenerated on Sat Jun 8 2019 20:28:55