Go to the documentation of this file.00001
00002
00003
00004
00005 try:
00006 import roslib; roslib.load_manifest('rospeex_core')
00007 except:
00008 pass
00009
00010 import os
00011 import sys
00012 import rospy
00013 import rospkg
00014 import datetime
00015 import platform
00016
00017
00018 from rospeex_msgs.msg import SignalProcessingResponse
00019 from rospeex_msgs.msg import SpeechSynthesisState
00020
00021
00022 from rospeex_core.spi import ConnectorInterface
00023 from rospeex_core.spi import WebAudioMonitor
00024 from rospeex_core.exceptions import SignalProcessingInterfaceException
00025 from rospeex_core.exceptions import WebAudioMonitorException
00026
00027
00028 class SignalProcessingInterface(object):
00029 """ SignalProcessingInterface class """
00030
00031 _SPI_RESPONSE_TOPIC_NAME = 'spi_res'
00032 _SS_STATE_TOPIC_NAME = 'ss_state'
00033
00034 def __init__(self):
00035 """ init function """
00036 package = rospkg.RosPack()
00037 rospeex_dir = package.get_path('rospeex_core')
00038 self._connector = None
00039 self._ip_addr = '127.0.0.1'
00040 self._app_dir = os.path.join(rospeex_dir, 'bin')
00041 self._controller = 'NICTmmcvController'
00042 self._webmonitor = 'monitorServer.nex'
00043 self._nict_mmcv = 'NICTmmcv'
00044 self._mmse_setting = 'NICTmmcv.mmse.ini'
00045 self._vad_setting = 'NICTmmcv.vad.ini'
00046 self._audio_dir = 'tmp'
00047 self._recv_port = 5002
00048 self._send_port = 16001
00049 self._websocket_port = 9000
00050 self._request_id = 0
00051 self._log_level = 'warn'
00052 self._audio_monitor_type = 'qt'
00053 self._audio_monitor = None
00054 self._pub_spi = None
00055
00056 def _ss_state_response(self, response):
00057 """ receive speech synthesis node state
00058 @param response: response data
00059 @type response: str
00060 """
00061 rospy.loginfo(response)
00062 self._connector.set_play_sound_state(response.play_state)
00063
00064 def _ui_response(self, data):
00065 """ receive user interface response
00066 @param data: voice data
00067 @type data: str
00068 """
00069 msg = SignalProcessingResponse()
00070 msg.header.user = rospy.get_name()
00071 msg.header.request_id = str(self._request_id)
00072 msg.data = data
00073 self._pub_spi.publish(msg)
00074 self._request_id += 1
00075
00076 now = datetime.datetime.now().strftime('%Y%m%d%H%M%S')
00077 filename = '%s.wav' % now
00078 filepath = os.path.join(self._audio_dir, filename)
00079 with open(filepath, 'wb') as wavefile:
00080 wavefile.write(data)
00081
00082 def _update_connection_parameter(self):
00083 """ update connection parameter """
00084 self._ip_addr = rospy.get_param('~ip_addr', self._ip_addr)
00085 self._recv_port = rospy.get_param('~recv_port', self._recv_port)
00086 self._send_port = rospy.get_param('~send_port', self._send_port)
00087 self._log_level = rospy.get_param('~log_level', self._log_level)
00088 self._websocket_port = rospy.get_param('~websocket_port', self._websocket_port)
00089 self._audio_monitor_type = rospy.get_param('~audio_monitor', self._audio_monitor_type)
00090 self._audio_dir = rospy.get_param('~audio_dir', self._audio_dir)
00091 self._audio_monitor = None
00092
00093
00094 rospy.loginfo('parameter:\n'\
00095 'tip_addr :%s\n'\
00096 ' \trecv_port :%s\n'\
00097 ' \tsend_port :%s\n'\
00098 ' \taudio_monitor :%s\n'\
00099 ' \twebsocket_port:%s'\
00100 %(self._ip_addr,\
00101 self._recv_port,\
00102 self._send_port,\
00103 self._audio_monitor_type,\
00104 self._websocket_port))
00105
00106 def _update_application_dir(self):
00107 """ update application directory. (32bit or 64bit) """
00108 arch = platform.architecture()
00109 try:
00110 if arch[0] == '32bit':
00111 self._app_dir = os.path.join(self._app_dir, 'x86')
00112 else:
00113 self._app_dir = os.path.join(self._app_dir, 'x64')
00114 except IndexError as err:
00115 rospy.info('platform.architecture() returns unexcepted value. Value: %s', str(arch))
00116 self._app_dir = os.path.join(self._app_dir, 'x64')
00117
00118 def shutdown(self):
00119 """ shutdown speech processing interface """
00120 if self._connector:
00121 self._connector.shutdown()
00122
00123 if self._audio_monitor:
00124 self._audio_monitor.exit()
00125
00126 def run(self):
00127 """ run application """
00128 rospy.init_node('rospeex_spi')
00129
00130
00131 self._pub_spi = rospy.Publisher(self._SPI_RESPONSE_TOPIC_NAME, SignalProcessingResponse)
00132 rospy.Subscriber(self._SS_STATE_TOPIC_NAME, SpeechSynthesisState, self._ss_state_response)
00133
00134
00135 self._update_connection_parameter()
00136
00137
00138 self._update_application_dir()
00139
00140
00141 if not os.path.exists(self._audio_dir):
00142 os.makedirs(self._audio_dir)
00143
00144
00145 self._connector = ConnectorInterface(
00146 app_dir=self._app_dir,
00147 controller=self._controller,
00148 nict_mmcv=self._nict_mmcv,
00149 mmse_setting=self._mmse_setting,
00150 vad_setting=self._vad_setting,
00151 ip_addr=self._ip_addr,
00152 recv_port=self._recv_port,
00153 send_port=self._send_port,
00154 log_level=self._log_level
00155 )
00156
00157 self._connector.register_callback(self._ui_response)
00158 self._connector.start()
00159
00160
00161 if self._audio_monitor_type == 'web':
00162 self._audio_monitor = WebAudioMonitor(
00163 app_dir=self._app_dir,
00164 app_name=self._webmonitor,
00165 send_port=self._send_port,
00166 recv_port=self._recv_port,
00167 websocket_port=self._websocket_port
00168 )
00169 self._audio_monitor.launch()
00170
00171
00172 rospy.loginfo('start signal processing interface node.')
00173 rate = rospy.Rate(100)
00174 while not rospy.is_shutdown():
00175 if self._audio_monitor:
00176 if not self._audio_monitor.is_alive():
00177 self._audio_monitor.exit()
00178 raise WebAudioMonitorException('WebAudioMonitor is terminated.')
00179 rate.sleep()
00180
00181
00182 def main():
00183 """ mian function """
00184 spi_node = None
00185
00186 try:
00187 spi_node = SignalProcessingInterface()
00188 spi_node.run()
00189
00190 except SignalProcessingInterfaceException as err:
00191 rospy.logfatal(str(err))
00192
00193 except rospy.ROSInterruptException as err:
00194 rospy.loginfo(str(err))
00195
00196 except WebAudioMonitorException as err:
00197 rospy.logfatal(str(err))
00198
00199 except Exception as err:
00200 rospy.logfatal(str(err))
00201
00202 finally:
00203 if spi_node is not None:
00204 spi_node.shutdown()
00205 return 0
00206
00207
00208 if __name__ == '__main__':
00209 sys.exit(main())