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


rospeex_core
Author(s): Komei Sugiura
autogenerated on Wed Aug 26 2015 16:10:30