simple_speek.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 """Copyright (c) 2016 Xu Zhihao (Howe).  All rights reserved.
00004 This program is free software; you can redistribute it and/or modify
00005 This programm is tested on kuboki base turtlebot."""
00006 
00007 
00008 from pyaudio import PyAudio
00009 from pyaudio import paInt16
00010 import json
00011 import os
00012 import sys
00013 import requests
00014 import vlc
00015 import rospy
00016 import getpass
00017 import numpy as np 
00018 from std_msgs.msg import String
00019 from threading import Lock
00020 
00021 "sudo apt-get install python-pygame"
00022 
00023 class speeker():
00024  def __init__(self):
00025   self.define()
00026   rospy.Subscriber('speak_string', String, self.SpeedCB, queue_size=1)
00027   rospy.Timer(rospy.Duration(self.ResponseSensitivity), self.TimerCB)
00028   rospy.spin()
00029     
00030     
00031  def TimerCB(self, event):
00032   with self.locker:
00033    self.TalkNow = True
00034  
00035  
00036     
00037  def SpeedCB(self, data):
00038  
00039   with self.locker:
00040   
00041    speak_string = data.data
00042  
00043    if self.TalkNow:
00044   
00045     self.WavName = speak_string
00046    
00047     self.TalkNow = False
00048   
00049     self.mp3file = '%s'%self.path + self.WavName + '.%s'%self.FORMAT
00050     
00051     if os.path.exists(r'%s'%self.mp3file):
00052    
00053      self.play_video(self.mp3file)
00054     
00055     else:
00056    
00057      self.speek(speak_string)
00058   
00059   
00060   
00061  def speek(self, speak_string):
00062   #获取token
00063   requestData = {       "grant_type":           self.Grant_type, 
00064                         "client_id":            self.Api_Key, 
00065                         "client_secret":        self.Secrect_Key}
00066   
00067   result = requests.post(url = self.Token_url, data = requestData)
00068   
00069   token_data = json.loads(result.text)
00070   
00071   if 'access_token' in token_data:  
00072    token = token_data['access_token']    #获取的token
00073    rospy.loginfo('token获取成功\n')#, 'token: ', token , '\n')
00074   else:
00075    rospy.loginfo("token获取失败\n")
00076 
00077   tex=speak_string
00078 
00079   #语音合成
00080   SpkData = {           "tex":          tex, 
00081                         "lan":          self.LAN, 
00082                         "tok":          token,
00083                         "ctp":          self.CTP,
00084                         "cuid":         self.USER_ID,
00085                         "spd":          self.SPEED,
00086                         "pit":          self.PIT,
00087                         "vol":          self.VOL,
00088                         "per":          self.PER[self.Gender]}
00089 
00090   re_voice=[]
00091 
00092   re = requests.post(url = self.Speeker_url, data = SpkData)
00093   
00094   if  'audio/mp3' in re.headers['content-type']: 
00095     
00096    file_=self.write_mp3(re)
00097 
00098   elif 'application/json' in  re.headers['content-type']: 
00099  
00100    spker_data=json.loads(re.text)
00101   
00102    self.Print_Response(spker_data)
00103   
00104    print '\n合成出错,原因: ',self.error_reason[spker_data[u'err_no']], '\n'
00105     
00106   else:
00107   
00108    pass
00109     
00110   if os.path.exists(r'%s'%file_):
00111   
00112    self.play_video(file_)
00113   
00114    self.mp3file = file_
00115   
00116   
00117   
00118  def define(self):
00119   
00120   self.error_reason = { 500:    '不支持输入',
00121                         501:    '输入参数不正确',
00122                         502:    'token验证失败',
00123                         503:    '合成后端错误'}
00124                      
00125   self.PER = {'women': 0, 'man': 1} #发音人选择,取值0-1, 0为女声,1为男声,默认为女声
00126   
00127   self.WavName = None
00128   
00129   if rospy.has_param('~Gender'):
00130    pass
00131   else:
00132    rospy.set_param('~Gender', 'women')
00133                         
00134   if rospy.has_param('~CTP'):
00135    pass
00136   else:
00137    rospy.set_param('~CTP', 1)
00138 
00139   if rospy.has_param('~LAN'):
00140    pass
00141   else:
00142    rospy.set_param('~LAN', 'zh')
00143                  
00144   if rospy.has_param('~USER_ID'):
00145    pass
00146   else:
00147    rospy.set_param('~USER_ID', '8168466')                     
00148                         
00149   if rospy.has_param('~SPEED'):
00150    pass
00151   else:
00152    rospy.set_param('~SPEED', 5)    
00153    
00154   if rospy.has_param('~PIT'):
00155    pass
00156   else:
00157    rospy.set_param('~PIT', 5)  
00158    
00159   if rospy.has_param('~VOL'):
00160    pass
00161   else:
00162    rospy.set_param('~VOL', 5)                     
00163 
00164   if rospy.has_param('~Api_Key'):
00165    pass
00166   else:
00167    rospy.set_param('~Api_Key', "pmUzrWcsA3Ce7RB5rSqsvQt2")    
00168  
00169   if rospy.has_param('~Secrect_Key'):
00170    pass
00171   else:
00172    rospy.set_param('~Secrect_Key', "d39ec848d016a8474c7c25e308b310c3")
00173 
00174   if rospy.has_param('~Grant_type'):
00175    pass
00176   else:
00177    rospy.set_param('~Grant_type', "client_credentials")
00178 
00179   if rospy.has_param('~Token_url'):
00180    pass
00181   else:
00182    rospy.set_param('~Token_url', "https://openapi.baidu.com/oauth/2.0/token")
00183    
00184   if rospy.has_param('~Speeker_url'):
00185    pass
00186   else:
00187    rospy.set_param('~Speeker_url', "http://tsn.baidu.com/text2audio")
00188 
00189   if rospy.has_param('~FORMAT'):
00190    pass
00191   else:
00192    rospy.set_param('~FORMAT', "mp3")
00193 
00194   if rospy.has_param('~ResponseSensitivity'):
00195    pass
00196   else:
00197    rospy.set_param('~ResponseSensitivity', 0.2)
00198    
00199   if rospy.has_param('~WorkSpaces'):
00200    pass
00201   else:
00202    rospy.set_param('~WorkSpaces', 'Xbot')
00203 
00204   self.Gender = rospy.get_param('~Gender')
00205  
00206   self.CTP = rospy.get_param('~CTP') # default 1
00207   
00208   self.LAN = rospy.get_param('~LAN') # default 'zh'
00209   
00210   self.USER_ID = rospy.get_param('~USER_ID') # default '8168466'             
00211 
00212   self.SPEED = rospy.get_param('~SPEED') # default 5 语速,取值0-9,默认为5中语速
00213 
00214   self.PIT = rospy.get_param('~PIT')     # default 5 音调,取值0-9,默认为5中语调
00215 
00216   self.VOL = rospy.get_param('~VOL')     # default 5 音量,取值0-9,默认为5中音量
00217 
00218   self.Api_Key = rospy.get_param('~Api_Key') # default "pmUzrWcsA3Ce7RB5rSqsvQt2"
00219   
00220   self.Secrect_Key = rospy.get_param('~Secrect_Key') # default "d39ec848d016a8474c7c25e308b310c3"
00221   
00222   self.Grant_type = rospy.get_param('~Grant_type') # default "client_credentials"
00223   
00224   self.Token_url = rospy.get_param('~Token_url') # default 'https://openapi.baidu.com/oauth/2.0/token'
00225   
00226   self.Speeker_url = rospy.get_param('~Speeker_url') # default 'http://tsn.baidu.com/text2audio'
00227  
00228   self.FORMAT = rospy.get_param('~FORMAT') # default 'mp3'
00229   
00230   self.ResponseSensitivity = float(rospy.get_param('~ResponseSensitivity'))
00231   
00232   self.WorkSpaces = rospy.get_param('~WorkSpaces')
00233   
00234   self.count = getpass.getuser()
00235   
00236   self.path='/home/%s/%s/src/simple_voice/src/'%(self.count, self.WorkSpaces)
00237   
00238   if not os.path.exists(self.path):
00239    os.makedirs(self.path)
00240   
00241   self.TalkNow = True
00242   
00243   self.locker = Lock()
00244   #self.SAMPLING_RATE =       16000    #取样频率
00245   
00246   #self.pub = rospy.Publisher('speak_status', String, queue_size=10)
00247   
00248  
00249  def Print_Response(self, data):
00250   for i in data:
00251    print '\t',i, ': ', data[i]
00252    pass
00253   
00254   
00255  def write_mp3(self,data):
00256   
00257   Voice_String=data.content
00258   
00259   #print self.WavName
00260   
00261   if len(self.WavName) > 12:
00262    FileSubName = self.WavName[:12]
00263   else:
00264    FileSubName = self.WavName
00265    
00266   file_=self.savemp3('%s'%self.path + FileSubName, Voice_String)
00267 
00268   return file_
00269  
00270  
00271  def current_path(self):
00272  
00273   path=sys.path[0] 
00274   
00275   if os.path.isdir(path):
00276    return path
00277    
00278   elif os.path.isfile(path):
00279    return os.path.dirname(path)
00280 
00281  def get_text(self):
00282   return raw_input('请输入想要合成的话语: ')
00283   
00284  def savemp3(self,filename,Voice_String):
00285   wf = open(filename+'.%s'%self.FORMAT, 'w') 
00286   wf.write(Voice_String) 
00287   wf.close() 
00288   return filename+'.%s'%self.FORMAT
00289 
00290 
00291  def play_video(self,file_):
00292   #print '\n start speaking ', "file://%s"%file_
00293   rospy.loginfo('start speaking ')
00294   player = vlc.MediaPlayer("file://%s"%file_)
00295   player.play()   
00296   rospy.sleep(1)
00297   while player.is_playing():
00298    pass
00299    #self.pub.publish('PENDING')
00300   rospy.loginfo('done\n')
00301   
00302 if __name__=="__main__":
00303  rospy.init_node('simple_speaker')
00304  rospy.loginfo( "initialization system")
00305  speeker()
00306  rospy.loginfo( "process done and quit")


simple_voice
Author(s): zhihao
autogenerated on Thu Jun 6 2019 21:21:00