node.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 
00004 # Import ROS packages
00005 import rospy
00006 
00007 # Import python libraries
00008 import subprocess
00009 
00010 # Import Messages
00011 from rospeex_msgs.msg import SpeechSynthesisRequest
00012 from rospeex_msgs.msg import SpeechSynthesisResponse
00013 from rospeex_msgs.msg import SpeechSynthesisHeader
00014 from rospeex_msgs.msg import SpeechSynthesisState
00015 
00016 # Import speech synthesis client
00017 from rospeex_core import exceptions as ext
00018 from rospeex_core.ss import Factory
00019 
00020 
00021 class SpeechSynthesis(object):
00022     """ SpeechSynthesis class """
00023     MY_NODE_NAME = 'rospeex_ss'
00024     REQUEST_TOPIC_NAME = 'ss_req'
00025     RESPONSE_TOPIC_NAME = 'ss_res'
00026     STATE_TOPIC_NAME = 'ss_state'
00027 
00028     def __init__(self):
00029         """ init function """
00030         self._pub_res = None
00031         self._pub_state = None
00032         self._user_request_dict = {}
00033 
00034     def _update_user_dictionary(self, header):
00035         """ renew user request dictionary
00036         @param header: request header
00037         @type  header: str
00038         """
00039         if header.user in self._user_request_dict:
00040             self._user_request_dict[header.user] += 1
00041             if int(header.request_id) != self._user_request_dict[header.user]:
00042                 # check request id
00043                 msg = 'invalid request id. user:{user} '\
00044                       'current id:{curr_id} previous id:{prev_id}'.format(
00045                         user=header.user,
00046                         curr_id=int(header.request_id),
00047                         prev_id=self._user_request_dict[header.user]
00048                         )
00049                 rospy.logwarn(msg)
00050             # update request id
00051             self._user_request_dict[header.user] = int(header.request_id)
00052 
00053         else:
00054             self._user_request_dict.update(
00055                 {header.user: int(header.request_id)}
00056             )
00057             rospy.logdebug('add new user:%s' % header.user)
00058 
00059     def _play_data(self, response):
00060         """ play audio data
00061         @param response: audio data
00062         @type  response: str
00063         """
00064         try:
00065             # play state = True
00066             self._publish_state(response.header, True)
00067 
00068             # write sound data
00069             tmp_file = open('output_tmp.dat', 'wb')
00070             tmp_file.write(response.data)
00071             tmp_file.close()
00072 
00073             # play sound
00074             args = ['aplay', '-q', 'output_tmp.dat']
00075             subprocess.check_output(args, stderr=subprocess.STDOUT)
00076 
00077         except IOError:
00078             rospy.logerr('aplay io error.')
00079 
00080         except OSError:
00081             rospy.logerr('aplay is not installed.')
00082 
00083         except subprocess.CalledProcessError:
00084             rospy.logerr('aplay return error value.')
00085 
00086         except:
00087             rospy.logerr('unknown exception.')
00088 
00089         finally:
00090             self._publish_state(response.header, False)
00091 
00092     @classmethod
00093     def _save_data(cls, file_name, data):
00094         """ save data to target file
00095         @param file_name: target file
00096         @type  file_name: str
00097         @param data: audio data
00098         @type  data: str
00099         """
00100         with open(file_name, 'wb') as tmp_file:
00101             tmp_file.write(data)
00102 
00103     def _publish_state(self, header, state):
00104         """ publish state topic
00105         @param header: speech synthesis header
00106         @type  header: str
00107         @param state: audio state
00108         @type  state: bool
00109         """
00110         ss_state = SpeechSynthesisState()
00111         ss_state.header = header
00112         ss_state.play_state = state
00113         self._pub_state.publish(ss_state)
00114         rospy.loginfo(ss_state)
00115 
00116     def _callback_func(self, request):
00117         """ callback functioin for ss_req topic
00118         @param request: request data
00119         @param request: str
00120         """
00121         rospy.loginfo(request)
00122         response = SpeechSynthesisResponse()
00123         response.header = request.header
00124         response.data = ''
00125 
00126         # update user dictionary
00127         self._update_user_dictionary(request.header)
00128 
00129         try:
00130             client = Factory.create(request.header.engine)
00131             response.data = client.request(
00132                 request.message,
00133                 request.header.language,
00134                 request.header.voice_font
00135             )
00136 
00137             request_type = request.header.request_type
00138 
00139             # if command is "say" play speech synthesis sound
00140             if request_type == SpeechSynthesisHeader.REQUEST_TYPE_SAY:
00141                 self._play_data(response)
00142 
00143             # if commsnd is "tts" save data
00144             elif request_type == SpeechSynthesisHeader.REQUEST_TYPE_TTS:
00145                 self._save_data(request.memo, response.data)
00146 
00147         except ext.SpeechSynthesisException as err:
00148             rospy.logerr('[SpeechSynthesisExcepton] ' + str(err))
00149             response.memo = str(err)
00150 
00151         except ext.ParameterException as err:
00152             rospy.logerr('[ParameterException] ' + str(err))
00153             response.memo = str(err)
00154 
00155         except ext.ServerException as err:
00156             rospy.logerr('[ServerException] ' + str(err))
00157             response.memo = str(err)
00158 
00159         # send speech synthesis response to subscribe node
00160         rospy.loginfo(response)
00161         self._pub_res.publish(response)
00162 
00163     def run(self):
00164         """ node main function """
00165         rospy.init_node(self.MY_NODE_NAME)
00166 
00167         rospy.Subscriber(
00168             self.REQUEST_TOPIC_NAME,
00169             SpeechSynthesisRequest,
00170             self._callback_func
00171         )
00172 
00173         self._pub_res = rospy.Publisher(
00174             self.RESPONSE_TOPIC_NAME,
00175             SpeechSynthesisResponse,
00176             queue_size=10
00177         )
00178 
00179         self._pub_state = rospy.Publisher(
00180             self.STATE_TOPIC_NAME,
00181             SpeechSynthesisState,
00182             queue_size=10
00183         )
00184 
00185         rospy.loginfo("start speech synthesis node")
00186         rospy.spin()
00187 
00188 
00189 def main():
00190     try:
00191         speech_synthesis_node = SpeechSynthesis()
00192         speech_synthesis_node.run()
00193 
00194     except rospy.ROSInterruptException:
00195         pass


rospeex_core
Author(s): Komei Sugiura
autogenerated on Thu Jun 6 2019 18:53:10