text_to_speech.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 
00004 import rospy
00005 from docomo_perception.msg import TextToSpeech
00006 from docomo_perception.srv import TextToSpeechService, TextToSpeechServiceResponse
00007 from sound_play.msg import *
00008 import actionlib
00009 
00010 import json
00011 import requests
00012 import yaml
00013 import tempfile
00014 import threading
00015 
00016 global APIHOST, APIKEY
00017 settings_path = "/var/lib/robot/docomo_tts_settings.yaml"
00018 
00019 class DocomoTextToSpeechNode(object):
00020     def __init__(self):
00021         self.sub = rospy.Subscriber("text_to_speech", TextToSpeech, self.callback)
00022         self.pub = rospy.Publisher("robotsound", SoundRequest)
00023         self.srv = rospy.Service("text_to_speech", TextToSpeechService, self.serviceCallback)
00024         self.ac = actionlib.SimpleActionClient("sound_play", SoundRequestAction)
00025         self.ac.wait_for_server()
00026         self.lock = threading.Lock()
00027 
00028     def _speakerID(self, m):
00029         if not m or m == TextToSpeech.FEMALE:
00030             return str(0)
00031         elif m == TextToSpeech.MALE:
00032             return str(1)
00033 
00034     def _speechRate(self, m):
00035         if not m: m = 1.00 # default
00036         if m < 0.50: m = 0.50
00037         elif m > 10.00: m = 10.00
00038         return "%.2f" % m
00039 
00040     def _powerRate(self, m):
00041         if not m: m = 1.00 # default
00042         if m < 0.00: m = 0.00
00043         elif m > 5.00: m = 5.00
00044         return "%.2f" % m
00045 
00046     def _voiceType(self, m):
00047         if not m: m = 0
00048         elif m < -2: m = -2
00049         elif m > 2: m = 2
00050         return str(m)
00051 
00052     def gen_voice(self, msg):
00053         dic = {
00054             "Command": "AP_Synth",
00055             "TextData": msg.text,
00056             "SpeakerID": self._speakerID(msg.gender),
00057             "SpeechRate": self._speechRate(msg.speed),
00058             "PowerRate": self._powerRate(msg.power),
00059             "VoiceType": self._voiceType(msg.type),
00060             "AudioFileFormat": "1"  # AAC
00061             }
00062         sendData = json.dumps(dic)
00063         url = "%s?APIKEY=%s" % (APIHOST, APIKEY)
00064         headers = { 'Content-type': 'application/json' }
00065         self.lock.acquire()
00066         urlres = requests.post(url, data=sendData, headers=headers)
00067         self.lock.release()
00068         rospy.loginfo("sent request %s -> %d", msg.text, urlres.status_code)
00069 
00070         if urlres.status_code is not requests.codes.ok:
00071             rospy.logerr("failed to send request: %d", urlres.status_code)
00072             return
00073 
00074         voice_path = tempfile.mktemp(prefix='docomo_tts_')
00075         with open(voice_path, 'w') as f:
00076             f.write(urlres.content)
00077         rospy.loginfo("received voice data: %s" % voice_path)
00078         return voice_path
00079 
00080     def callback(self, msg):
00081         voice_path = self.gen_voice(msg)
00082         # command play sound
00083         pub_msg = SoundRequest()
00084         pub_msg.sound = SoundRequest.PLAY_FILE
00085         pub_msg.command = SoundRequest.PLAY_ONCE
00086         pub_msg.arg = voice_path
00087         self.pub.publish(pub_msg)
00088 
00089     def serviceCallback(self, req):
00090         voice_path = self.gen_voice(req.speech)
00091 
00092         pub_msg = SoundRequest()
00093         pub_msg.sound = SoundRequest.PLAY_FILE
00094         pub_msg.command = SoundRequest.PLAY_ONCE
00095         pub_msg.arg = voice_path
00096 
00097         goal = SoundRequestGoal()
00098         goal.sound_request = pub_msg
00099         self.ac.send_goal(goal)
00100         self.ac.wait_for_result()
00101         res = TextToSpeechServiceResponse()
00102         return res
00103 
00104 def load_tts_settings():
00105     global APIHOST, APIKEY
00106 
00107     try:
00108         with open(settings_path) as f:
00109             key = yaml.load(f)
00110             APIHOST = key['APIHOST']
00111             APIKEY = key['APIKEY']
00112             rospy.loginfo("loaded settings")
00113     except IOError as e:
00114         rospy.logerr('"%s" not found : %s' % (settings_path, e))
00115         exit(-1)
00116     except Exception as e:
00117         rospy.logerr("failed to load settings: %s", e)
00118         rospy.logerr("check if exists valid setting file in %s", settings_path)
00119         exit(-1)
00120 
00121 
00122 if __name__ == '__main__':
00123     rospy.init_node("docomo_tts_node")
00124     t = DocomoTextToSpeechNode()
00125     load_tts_settings()
00126     rospy.spin()


docomo_perception
Author(s): Yuki Furuta
autogenerated on Thu Jun 6 2019 18:03:42