-
Notifications
You must be signed in to change notification settings - Fork 0
/
module_speechrecognition.py
519 lines (393 loc) · 18.4 KB
/
module_speechrecognition.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
# -*- coding: utf-8 -*-
###########################################################
# Retrieve robot audio buffer and do google speech recognition
#
# Syntax:
# python scriptname --pip <ip> --pport <port>
#
# --pip <ip>: specify the ip of your robot (without specification it will use the NAO_IP defined below)
#
# Author: Johannes Bramauer, Vienna University of Technology
# Created: May 30, 2018
# License: MIT
#
###########################################################
#### THIS IS UP-TO-DATE PY CODE AS IN PEPPER NAO
import socket
from raw_to_wav import rawToWav
NAO_IP = "10.50.20.38" # default, for running on Pepper
NAO_PORT = 9559
from optparse import OptionParser
import naoqi
import numpy as np
import time
import sys
import threading
from naoqi import ALProxy
from google import Recognizer, UnknownValueError, RequestError
from numpy import sqrt, mean, square
import traceback
RECORDING_DURATION = 15 # seconds, maximum recording time, also default value for startRecording(), Google Speech API only accepts up to about 10-15 seconds
LOOKAHEAD_DURATION = 1.0 # seconds, for auto-detect mode: amount of seconds before the threshold trigger that will be included in the request
IDLE_RELEASE_TIME = 1.0 # seconds, for auto-detect mode: idle time (RMS below threshold) after which we stop recording and recognize
HOLD_TIME = 2.0 # seconds, minimum recording time after we started recording (autodetection)
SAMPLE_RATE = 48000 # Hz, be careful changing this, both google and Naoqi have requirements!
CALIBRATION_DURATION = 5 # seconds, timespan during which calibration is performed (summing up RMS values and calculating mean)
CALIBRATION_THRESHOLD_FACTOR = 1.5 # factor the calculated mean RMS gets multiplied by to determine the auto detection threshold (after calibration)
DEFAULT_LANGUAGE = "en-us" # RFC5646 language tag, e.g. "en-us", "de-de", "fr-fr",... <http://stackoverflow.com/a/14302134>
WRITE_WAV_FILE = False # write the recorded audio to "out.wav" before sending it to google. intended for debugging purposes
PRINT_RMS = False # prints the calculated RMS value to the console, useful for setting the threshold
PREBUFFER_WHEN_STOP = False # Fills pre-buffer with last samples when stopping recording. WARNING: has performance issues!
class SpeechRecognitionModule(naoqi.ALModule):
"""
Use this object to get call back from the ALMemory of the naoqi world.
Your callback needs to be a method with two parameter (variable name, value).
"""
def __init__( self, strModuleName, strNaoIp ):
try:
naoqi.ALModule.__init__(self, strModuleName )
# is these 2 line necessary? what do they do?
# just copied them from the examples...
self.BIND_PYTHON( self.getName(),"callback" )
self.strNaoIp = strNaoIp
# declare event to ALMemory so other modules can subscribe
self.memory = naoqi.ALProxy("ALMemory")
self.memory.declareEvent("SpeechRecognition")
# flag to indicate if subscribed to audio events
self.isStarted = False
# flag to indicate if we are currently recording audio
self.isRecording = False
self.startRecordingTimestamp = 0
self.recordingDuration = RECORDING_DURATION
# flag to indicate if auto speech detection is enabled
self.isAutoDetectionEnabled = True
self.autoDetectionThreshold = 4 # TODO: find a default value that works fine so we don't need to calibrate every time
# flag to indicate if we are calibrating
self.isCalibrating = False
self.startCalibrationTimestamp = 0
# RMS calculation variables
self.framesCount = 0
self.rmsSum = 0 # used to sum up rms results and calculate average
self.lastTimeRMSPeak = 0
# audio buffer
self.buffer = []
self.preBuffer = []
self.preBufferLength = 0 # length in samples (len(self.preBuffer) just counts entries)
# init parameters
self.language = DEFAULT_LANGUAGE
self.idleReleaseTime = IDLE_RELEASE_TIME
self.holdTime = HOLD_TIME
self.lookaheadBufferSize = LOOKAHEAD_DURATION * SAMPLE_RATE
# counter for wav file output
self.fileCounter = 0
except BaseException, err:
print( "ERR: SpeechRecognitionModule: loading error: %s" % str(err) )
# __init__ - end
def __del__( self ):
print( "INF: SpeechRecognitionModule.__del__: cleaning everything" )
self.stop()
def start( self ):
if(self.isStarted):
print("INF: SpeechRecognitionModule.start: already running")
return
print("INF: SpeechRecognitionModule: starting!")
self.isStarted = True
audio = naoqi.ALProxy( "ALAudioDevice")
nNbrChannelFlag = 0 # ALL_Channels: 0, AL::LEFTCHANNEL: 1, AL::RIGHTCHANNEL: 2 AL::FRONTCHANNEL: 3 or AL::REARCHANNEL: 4.
nDeinterleave = 0
audio.setClientPreferences( self.getName(), SAMPLE_RATE, nNbrChannelFlag, nDeinterleave ) # setting same as default generate a bug !?!
audio.subscribe( self.getName() )
# Play the blip sound
au = session.service("ALAudioPlayer")
au.playFile("/home/nao/blip.mp3", 1, 0)
def pause(self):
print("INF: SpeechRecognitionModule.pause: stopping")
if (self.isStarted == False):
print("INF: SpeechRecognitionModule.stop: not running")
return
self.isStarted = False
audio = naoqi.ALProxy("ALAudioDevice", self.strNaoIp, NAO_PORT)
audio.unsubscribe(self.getName())
print("INF: SpeechRecognitionModule: stopped!")
def stop( self ):
self.pause()
def processRemote( self, nbOfChannels, nbrOfSamplesByChannel, aTimeStamp, buffer ):
#print("INF: SpeechRecognitionModule: Processing '%s' channels" % nbOfChannels)
# calculate a decimal seconds timestamp
timestamp = float (str(aTimeStamp[0]) + "." + str(aTimeStamp[1]))
# put whole function in a try/except to be able to see the stracktrace
try:
aSoundDataInterlaced = np.fromstring( str(buffer), dtype=np.int16 )
aSoundData = np.reshape( aSoundDataInterlaced, (nbOfChannels, nbrOfSamplesByChannel), 'F' )
# compute RMS, handle autodetection and calibration
if( self.isCalibrating or self.isAutoDetectionEnabled or self.isRecording):
# compute the rms level on front mic
rmsMicFront = self.calcRMSLevel(self.convertStr2SignedInt(aSoundData[0]))
if (rmsMicFront >= self.autoDetectionThreshold):
# save timestamp when we last had and RMS > threshold
self.lastTimeRMSPeak = timestamp
# start recording if we are not doing so already
if (self.isAutoDetectionEnabled and not self.isRecording and not self.isCalibrating):
self.startRecording()
# perform calibration
if( self.isCalibrating):
if(self.startCalibrationTimestamp <= 0):
# we are starting to calibrate, save timestamp
# to track how long we are doing this
self.startCalibrationTimestamp = timestamp
elif(timestamp - self.startCalibrationTimestamp >= CALIBRATION_DURATION):
# time's up, we're done!
self.stopCalibration()
# sum rms values of the frames
# keep track of how many frames we sum up
# to calculate mean afterwards
self.rmsSum += rmsMicFront
self.framesCount = self.framesCount + 1
if(PRINT_RMS):
# for debug purposes
# also use it to find a good threshold value for auto detection
print 'Mic RMS: ' + str(rmsMicFront)
if( False ):
# compute average
aAvgValue = np.mean( aSoundData, axis = 1 )
print( "avg: %s" % aAvgValue )
if( False ):
# compute fft
nBlockSize = nbrOfSamplesByChannel
signal = aSoundData[0] * np.hanning( nBlockSize )
aFft = ( np.fft.rfft(signal) / nBlockSize )
print aFft
if( False ):
# compute peak
aPeakValue = np.max( aSoundData )
if( aPeakValue > 16000 ):
print( "Peak: %s" % aPeakValue )
if(not self.isCalibrating):
if(self.isRecording):
# write to buffer
self.buffer.append(aSoundData)
if (self.startRecordingTimestamp <= 0):
# initialize timestamp when we start recording
self.startRecordingTimestamp = timestamp
elif ((timestamp - self.startRecordingTimestamp) > self.recordingDuration):
print('stop after max recording duration')
# check how long we are recording
self.stopRecordingAndRecognize()
# stop recording after idle time (and recording at least hold time)
# lastTimeRMSPeak is 0 if no peak occured
if (timestamp - self.lastTimeRMSPeak >= self.idleReleaseTime) and (
timestamp - self.startRecordingTimestamp >= self.holdTime):
print ('stopping after idle/hold time')
self.stopRecordingAndRecognize()
else:
# constantly record into prebuffer for lookahead
self.preBuffer.append(aSoundData)
self.preBufferLength += len(aSoundData[0])
# remove first (oldest) item if the buffer gets bigger than required
# removes one block of samples as we store a list of lists...
overshoot = (self.preBufferLength - self.lookaheadBufferSize)
if((overshoot > 0) and (len(self.preBuffer) > 0)):
self.preBufferLength -= len(self.preBuffer.pop(0)[0])
except:
# i did this so i could see the stracktrace as the thread otherwise just silently failed
traceback.print_exc()
# processRemote - end
def calcRMSLevel(self, data):
rms = (sqrt(mean(square(data))))
# TODO: maybe a log would be better for threshold?
#rms = 20 * np.log10(np.sqrt(np.sum(np.power(data, 2) / len(data))))
return rms
def version( self ):
return "1.1"
# use this method to manually start recording (works with both autodetection enabled or disabled)
# the recording will stop after the signal is below the threshold for IDLE_RELEASE_TIME seconds,
# but will at least record for HOLD_TIME seconds
def startRecording(self):
if(self.isRecording):
print("INF: SpeechRecognitionModule.startRecording: already recording")
return
print("INF: Starting to record audio")
# start recording
self.startRecordingTimestamp = 0
self.lastTimeRMSPeak = 0
self.buffer = self.preBuffer
#self.preBuffer = []
self.isRecording = True
return
def stopRecordingAndRecognize(self):
if(self.isRecording == False):
print("INF: SpeechRecognitionModule.stopRecordingAndRecognize: not recording")
return
print("INF: stopping recording and recognizing")
# TODO: choose which mic channel to use
# can we use the sound direction module for this?
# buffer is a list of nparrays we now concat into one array
# and the slice out the first mic channel
slice = np.concatenate(self.buffer, axis=1)[0]
# initialize preBuffer with last samples to fix cut off words
# loop through buffer and count samples until prebuffer is full
# TODO: performance issues!
if (PREBUFFER_WHEN_STOP):
sampleCounter = 0
itemCounter = 0
for i in reversed(self.preBuffer):
sampleCounter += len(i[0])
if(sampleCounter > self.lookaheadBufferSize):
break
itemCounter += 1
start = len(self.buffer) - itemCounter
self.preBuffer = self.buffer[start:]
else:
# don't copy to prebuffer
self.preBuffer = []
# start new worker thread to do the http call and some processing
# copy slice to be thread safe!
# TODO: make a job queue so we don't start a new thread for each recognition
threading.Thread(target=self.recognize, args=(slice.copy(), )).start()
# reset flag
self.isRecording = False
return
def calibrate(self):
self.isCalibrating = True
self.framesCount = 0
self.startCalibrationTimestamp = 0
print("INF: starting calibration")
if(self.isStarted == False):
self.start()
return
def stopCalibration(self):
if(self.isCalibrating == False):
print("INF: SpeechRecognitionModule.stopCalibration: not calibrating")
return
self.isCalibrating = False
# calculate avg rms over self.framesCount
self.threshold = CALIBRATION_THRESHOLD_FACTOR * (self.rmsSum / self.framesCount)
print 'calibration done, RMS threshold is: ' + str(self.threshold)
return
def enableAutoDetection(self):
self.isAutoDetectionEnabled = True
print("INF: autoDetection enabled")
return
def disableAutoDetection(self):
self.isAutoDetectionEnabled = False
return
def setLanguage(self, language = DEFAULT_LANGUAGE):
self.language = language
return
# used for RMS calculation
def convertStr2SignedInt(self, data):
"""
This function takes a string containing 16 bits little endian sound
samples as input and returns a vector containing the 16 bits sound
samples values converted between -1 and 1.
"""
# from the naoqi sample, but rewritten to use numpy methods instead of for loops
lsb = data[0::2]
msb = data[1::2]
# don't remove the .0, otherwise overflow!
rms_data = np.add(lsb, np.multiply(msb, 256.0))
# gives and array that contains -65536 on every position where signedData is > 32768
sign_correction = np.select([rms_data>=32768], [-65536])
# add the two to get the correct signed values
rms_data = np.add(rms_data, sign_correction)
# normalize values to -1.0 ... +1.0
rms_data = np.divide(rms_data, 32768.0)
return rms_data
def recognize(self, data):
# print 'sending %d bytes' % len(data)
if (WRITE_WAV_FILE):
# write to file
filename = "out" + str(self.fileCounter)
self.fileCounter += 1
outfile = open(filename + ".raw", "wb")
data.tofile(outfile)
outfile.close()
rawToWav(filename)
buffer = np.getbuffer(data)
r = Recognizer()
#r.dynamic_energy_threshold = True
#r.pause_threshold = 2
#r.energy_threshold = 4000 #higher to reduce ambient(non-speaking energy), so that while not speaking, it wont try to recognize
try:
result = r.recognize_google(audio_data=buffer, samplerate=SAMPLE_RATE, language=self.language)
self.memory.raiseEvent("SpeechRecognition", result)
print 'RESULT: ' + result
return result
except UnknownValueError:
print 'ERR: Recognition error'
result = ''
print(result)
except RequestError, e:
print 'ERR: ' + str(e)
except socket.timeout:
print 'ERR: Socket timeout'
except:
print 'ERR: Unknown, probably timeout ' + str(sys.exc_info()[0])
def setAutoDetectionThreshold(self, threshold):
self.autoDetectionThreshold = threshold
def setIdleReleaseTime(self, releaseTime):
self.idleReleaseTime = releaseTime
def setHoldTime(self, holdTime):
self.holdTime = holdTime
def setMaxRecordingDuration(self, duration):
self.recordingDuration = duration
def setLookaheadDuration(self, duration):
self.lookaheadBufferSize = duration * SAMPLE_RATE
self.preBuffer = []
self.preBufferLength = 0
# SpeechRecognition - end
def getAudioDuration(self):
return len(self.audio_data)/48000.0
def main():
""" Main entry point
"""
parser = OptionParser()
parser.add_option("--pip",
help="Parent broker port. The IP address or your robot",
dest="pip")
parser.add_option("--pport",
help="Parent broker port. The port NAOqi is listening to",
dest="pport",
type="int")
parser.set_defaults(
pip=NAO_IP,
pport=NAO_PORT)
(opts, args_) = parser.parse_args()
pip = opts.pip
pport = opts.pport
# We need this broker to be able to construct
# NAOqi modules and subscribe to other modules
# The broker must stay alive until the program exists
myBroker = naoqi.ALBroker("myBroker",
"0.0.0.0", # listen to anyone
0, # find a free port and use it
pip, # parent broker IP
pport) # parent broker port
try:
p = ALProxy("SpeechRecognition")
p.exit() # kill previous instance, useful for developing ;)
except:
pass
# Reinstantiate module
# Warning: SpeechRecognition must be a global variable
# The name given to the constructor must be the name of the
# variable
global SpeechRecognition
SpeechRecognition = SpeechRecognitionModule("SpeechRecognition", pip)
# uncomment for debug purposes
# usually a subscribing client will call start() from ALProxy
#SpeechRecognition.start()
#SpeechRecognition.startRecording()
#SpeechRecognition.calibrate()
#SpeechRecognition.enableAutoDetection()
#SpeechRecognition.startRecording()
try:
while True:
time.sleep(1)
except KeyboardInterrupt:
print
print "Interrupted by user, shutting down"
myBroker.shutdown()
sys.exit(0)
if __name__ == "__main__":
main()