more stable implementation of speech stuff
This commit is contained in:
@@ -10,7 +10,6 @@ from teleoperation.msg import RequestSpeechAction, RequestSpeechResult
|
||||
|
||||
speech_broker = None
|
||||
almem = None
|
||||
r = False
|
||||
|
||||
|
||||
def request_speech(goal):
|
||||
@@ -18,7 +17,9 @@ def request_speech(goal):
|
||||
sas.set_succeeded(RequestSpeechResult(word=''))
|
||||
return
|
||||
|
||||
while not sas.is_preempt_requested() and not speech_detector.have_word():
|
||||
while (not sas.is_preempt_requested() and
|
||||
not speech_detector.have_word() and
|
||||
not rospy.is_shutdown()):
|
||||
rospy.Rate(10).sleep()
|
||||
|
||||
if speech_detector.have_word():
|
||||
@@ -40,16 +41,24 @@ class SpeechDetectorModule(ALModule):
|
||||
self.asr = ALProxy('ALSpeechRecognition')
|
||||
self.tts = ALProxy('ALTextToSpeech')
|
||||
self.asr.setLanguage('English')
|
||||
self.running = False
|
||||
almem.subscribeToEvent("WordRecognized",
|
||||
"speech_detector",
|
||||
"on_word_recognized")
|
||||
self.asr.pause(True)
|
||||
self._busy = False
|
||||
|
||||
def start_speech(self, voc):
|
||||
if self.running:
|
||||
def get_status(self):
|
||||
print(almem.getData('ALSpeechRecognition/Status'))
|
||||
|
||||
def start_speech(self, voc, resume=False):
|
||||
if self._busy != resume:
|
||||
return False
|
||||
self.voc = voc
|
||||
self.asr.setVocabulary(voc, False)
|
||||
self.asr.subscribe(self.subid)
|
||||
if not resume:
|
||||
self.voc = voc
|
||||
self.asr.setVocabulary(voc, False)
|
||||
self.asr.subscribe(self.subid)
|
||||
self.asr.pause(False)
|
||||
self.running = True
|
||||
self._busy = True
|
||||
return True
|
||||
|
||||
def have_word(self):
|
||||
@@ -60,23 +69,26 @@ class SpeechDetectorModule(ALModule):
|
||||
self.recognized = None
|
||||
return result
|
||||
|
||||
def stop_speech(self):
|
||||
if not self.running:
|
||||
def stop_speech(self, pause=False):
|
||||
if not self._busy:
|
||||
return
|
||||
self.asr.unsubscribe(self.subid)
|
||||
self.asr.pause(True)
|
||||
self.running = False
|
||||
if not pause:
|
||||
self.asr.unsubscribe(self.subid)
|
||||
self._busy = False
|
||||
|
||||
def on_word_recognized(self, *_args):
|
||||
word, conf = almem.getData('WordRecognized')
|
||||
print(word, conf)
|
||||
if conf > 0.4:
|
||||
self.stop_speech()
|
||||
self.stop_speech(pause=True)
|
||||
self.tts.say(word)
|
||||
self.recognized = word
|
||||
else:
|
||||
self.stop_speech()
|
||||
else:
|
||||
self.stop_speech(pause=True)
|
||||
self.tts.say('I didn\'t understand. Please repeat')
|
||||
self.start_speech(self.voc)
|
||||
self.start_speech(self.voc, resume=True)
|
||||
|
||||
|
||||
|
||||
@@ -84,21 +96,16 @@ if __name__ == '__main__':
|
||||
rospy.init_node('speech_server')
|
||||
speech_broker = ALBroker('speech_broker', '0.0.0.0', 0,
|
||||
os.environ['NAO_IP'], 9559)
|
||||
speech_detector = SpeechDetectorModule('speech_detector')
|
||||
almem = ALProxy('ALMemory')
|
||||
almem.subscribeToEvent("WordRecognized",
|
||||
"speech_detector",
|
||||
"on_word_recognized")
|
||||
speech_detector.asr.pause(True)
|
||||
speech_detector = SpeechDetectorModule('speech_detector')
|
||||
sas = actionlib.SimpleActionServer('speech_server', RequestSpeechAction,
|
||||
execute_cb=request_speech,
|
||||
auto_start=False)
|
||||
sas.start()
|
||||
|
||||
while not rospy.is_shutdown():
|
||||
rospy.Rate(4).sleep()
|
||||
|
||||
if speech_detector.running:
|
||||
speech_detector.stop_speech()
|
||||
rospy.Rate(1).sleep()
|
||||
while sas.is_active():
|
||||
pass
|
||||
|
||||
speech_broker.shutdown()
|
||||
|
||||
Reference in New Issue
Block a user