00001
00002
00003
00004 try:
00005 import roslib; roslib.load_manifest('rospeex')
00006 except:
00007 pass
00008
00009 import os
00010 import struct
00011 import subprocess
00012 import traceback
00013 import threading
00014
00015
00016 import logging
00017 logger = logging.getLogger(__name__)
00018 logdebug = logger.debug
00019 loginfo = logger.info
00020 logwarn = logger.warn
00021 logdebug = logger.error
00022 logfatal = logger.critical
00023
00024 try:
00025 import rospy
00026 logdebug = rospy.logdebug
00027 loginfo = rospy.loginfo
00028 logwarn = rospy.logwarn
00029 logerr = rospy.logerr
00030 logfatal = rospy.logfatal
00031 except:
00032 pass
00033
00034 from rospeex_core.validators import accepts
00035 from rospeex_core.exceptions import SignalProcessingInterfaceException
00036
00037 class WaveFile(object):
00038 """ Wave file converter class """
00039
00040 def __init__(self):
00041 """ initialize function """
00042 self._data = ''
00043 self._header = ''
00044 self._count = 0
00045
00046
00047 def build(self, data):
00048 """
00049 build wave file
00050 @param data: voice data
00051 @type data: str
00052 """
00053 self._create_header(len(data))
00054 self._data = self._header
00055 fmt = '%dH' %len(data)
00056 pack_data = struct.pack(fmt, *data)
00057 self._data += pack_data
00058 return self._data
00059
00060
00061 def _create_header(self, data_size):
00062 """
00063 create wave file header
00064 @param data_size: wav data part size
00065 @type data_size: int
00066 """
00067 self._header = []
00068 fmt_chunk = struct.pack('4s I 2H 2I 2H', *[
00069 'fmt ',
00070 16,
00071 1,
00072 1,
00073 16000,
00074 32000,
00075 2,
00076 16])
00077
00078 data_chunk = struct.pack('4s I', *[
00079 'data',
00080 data_size*2])
00081
00082 file_size = len(data_chunk) + len(fmt_chunk) + 12 - 8 + data_size*2
00083 wav_header = struct.pack('4s I 4s', *[
00084 'RIFF',
00085 file_size,
00086 'WAVE'])
00087
00088 self._header = wav_header + fmt_chunk + data_chunk
00089
00090
00091 class Connector(object):
00092 """ AppConnector class """
00093
00094 def __init__(self, app_dir, controller, nict_mmcv, mmse_setting, vad_setting, ip_addr, recv_port, send_port, log_level):
00095 """
00096 initialize function
00097 @param app_dir: application directory
00098 @type app_dir:
00099 @param controller:
00100 @type controller:
00101 @param nict_mmcv:
00102 @type nict_mmcv:
00103 @param mmse_setting:
00104 @type mmse_setting:
00105 @param vad_setting:
00106 @type vad_setting:
00107 @param ip_addr:
00108 @type ip_addr:
00109 @param recv_port:
00110 @type recv_port:
00111 @param send_port:
00112 @type send_port:
00113 @param log_level:
00114 @type log_level:
00115 """
00116 self._app_dir = app_dir
00117 self._controller = os.path.join(app_dir, controller)
00118 self._nict_mmcv = os.path.join(app_dir, nict_mmcv)
00119 self._mmse_setting = os.path.join(app_dir, mmse_setting)
00120 self._vad_setting = os.path.join(app_dir, vad_setting)
00121 self._cwd = app_dir
00122 self._ip_addr = ip_addr
00123 self._recv_port = recv_port
00124 self._send_port = send_port
00125 self._log_level = log_level
00126 self._process = None
00127
00128
00129 def launch(self):
00130 """
00131 launch application
00132 @raise SignalProcessingInterfaceException: NICTmmcvController is not installed.
00133 """
00134
00135 args = [self._controller,
00136 '-i', self._ip_addr,
00137 '-m', self._mmse_setting,
00138 '-v', self._vad_setting,
00139 '-b', self._nict_mmcv,
00140 '-l', self._log_level,
00141 '-s', str(self._send_port),
00142 '-c', str(self._recv_port)]
00143
00144 options = {'stdin': subprocess.PIPE,
00145 'stdout': subprocess.PIPE,
00146 'cwd': self._cwd,
00147 'close_fds': True}
00148
00149
00150 try:
00151 self._process = subprocess.Popen(args, **options)
00152
00153 except (OSError, ValueError) as err:
00154 raise SignalProcessingInterfaceException('NICTmmcvController is not installed. Exception:%s' % str(err))
00155
00156 except Exception as err:
00157 raise SignalProcessingInterfaceException('unknown exception. Traceback: %s' % traceback.format_exc())
00158
00159
00160 def read(self, data_size):
00161 """
00162 read data from stdout
00163 @param data_size: read data size
00164 @type data_size: integer
00165 @return: read data
00166 @rtype: str
00167 @raize: SignalProcessingInterfaceException: NICTmmcvController is not launch
00168 """
00169 if self._process is None:
00170 raise SignalProcessingInterfaceException('NICTmmcvController is not launched.')
00171
00172 return self._process.stdout.read(data_size)
00173
00174
00175 def write(self, data):
00176 """
00177 write data
00178 @param data: write data
00179 @type data: str
00180 @raize: SignalProcessingInterfaceException: NICTmmcvController is not launch
00181 """
00182 if self._process is None:
00183 raise SignalProcessingInterfaceException('NICTmmcvController is not launched.')
00184
00185 self._process.stdin.write(data)
00186 self._process.stdin.flush()
00187
00188
00189 def poll(self):
00190 """
00191 polling process
00192 @return errorcode
00193 @rtype errorcode
00194 @raize: SignalProcessingInterfaceException: NICTmmcvController is not launch
00195 """
00196 if self._process is None:
00197 raise SignalProcessingInterfaceException('NICTmmcvController is not launch.')
00198
00199 return self._process.poll()
00200
00201
00202 def shutdown(self):
00203 """ shutdown application """
00204 if self._process is not None:
00205 self._process.kill()
00206 self._process.wait()
00207 self._process = None
00208
00209
00210 class FrameSyncHeader:
00211 """
00212 Frame Sync Header class
00213 """
00214 DATA_MARK = 0
00215 START_MARK = 1
00216 END_MARK = 2
00217 TOF_MARK = 9
00218 EOF_MARK = 10
00219
00220
00221 class ConnectorInterface(threading.Thread):
00222 """
00223 application controller interface class
00224 """
00225
00226 @accepts(app_dir=basestring, controller=basestring, nict_mmcv=basestring, mmse_setting=basestring, vad_setting=basestring, ip_addr=basestring, recv_port=int, send_port=int)
00227 def __init__(self, app_dir, controller, nict_mmcv, mmse_setting, vad_setting, ip_addr, recv_port, send_port, log_level):
00228 """
00229 initialize function
00230
00231 @param app_dir: application directory
00232 @type app_dir: str
00233 @param controller: controller name
00234 @type controller: str
00235 @param nict_mmcv: mmcv applicaton path
00236 @type nict_mmcv: str
00237 @param mmse_setting: mmse setting file path
00238 @type mmse_setting: str
00239 @param vad_setting: vad setting file path
00240 @type vad_setting: str
00241 @param ip_addr: controller ip address
00242 @type ip_addr: str
00243 @param recv_port: data receive port
00244 @type recv_port: int
00245 @param send_port: data send port
00246 @type send_port: int
00247 @param log_level: loglevel
00248 @type log_level: str
00249 """
00250 threading.Thread.__init__(self)
00251 self._connector = Connector(app_dir, controller, nict_mmcv, mmse_setting, vad_setting, ip_addr, recv_port, send_port, log_level)
00252 self._voice_tmp = []
00253 self._voice_state = -1
00254 self._is_shutdown = False
00255 self._callback = None
00256 self.FRAME_SYNC_DATA_SIZE = 320
00257 self.FRAME_SYNC_HEADER_SIZE = 4
00258 self.FRAME_SYNC_SIZE = self.FRAME_SYNC_HEADER_SIZE + self.FRAME_SYNC_DATA_SIZE
00259
00260 def shutdown(self):
00261 """
00262 shutdown application
00263 """
00264 self._is_shutdown = True
00265
00266 def register_callback(self, callback):
00267 """
00268 get wav data
00269 @param callback: wav file callback
00270 @type callback: function
00271 """
00272 self._callback = callback
00273
00274
00275 def set_play_sound_state(self, state):
00276 """
00277 set play sound state
00278 @param state: play sound state
00279 @type state: True for playing sound.
00280 False for NOT playing sound.
00281 """
00282 msg = 'play_sound_on\n\n'
00283
00284 if state == False:
00285 msg = 'play_sound_off\n\n'
00286
00287 self._connector.write(msg)
00288
00289
00290 def run(self):
00291 """
00292 thread main
00293 """
00294
00295 self._connector.launch()
00296
00297
00298 while self._is_shutdown == False:
00299
00300 if self._connector.poll() is not None:
00301 raise SignalProcessingInterfaceException('NICTmmcvController is terminated.')
00302
00303
00304 recv_data = self._connector.read(self.FRAME_SYNC_SIZE)
00305 if len(recv_data) == self.FRAME_SYNC_SIZE:
00306 header = struct.unpack('<I', recv_data[0:self.FRAME_SYNC_HEADER_SIZE])[0]
00307
00308 if header == FrameSyncHeader.DATA_MARK:
00309 if self._voice_state == FrameSyncHeader.START_MARK:
00310 fmt = '<%dH'%(self.FRAME_SYNC_DATA_SIZE/2)
00311 voice_data = struct.unpack(fmt, recv_data[self.FRAME_SYNC_HEADER_SIZE:self.FRAME_SYNC_SIZE])
00312 self._voice_tmp.extend(list(voice_data))
00313
00314 elif header == FrameSyncHeader.START_MARK:
00315 loginfo('voice start ----------------------->')
00316 self._voice_state = header
00317 self._voice_tmp = []
00318
00319 elif header == FrameSyncHeader.END_MARK:
00320 if self._voice_state == FrameSyncHeader.START_MARK:
00321 loginfo('voice end <-------------------------')
00322 self._voice_state = header
00323 wav = WaveFile()
00324 wav_data = wav.build(self._voice_tmp)
00325 self._voice_tmp = []
00326 if self._callback != None:
00327 self._callback(wav_data)
00328
00329 elif header == FrameSyncHeader.TOF_MARK or header == FrameSyncHeader.EOF_MARK:
00330 self._voice_state = header
00331 self._voice_state = []
00332 else:
00333 raise SignalProcessingInterfaceException('Invalid header: %d' %header)
00334
00335
00336 self._connector.shutdown()
00337
00338