38 from dynamic_reconfigure.server
import Server
as ReConfServer
39 import dynamic_reconfigure.client
40 from naoqi_driver_py.cfg
import NaoqiSpeechConfig
as NodeConfig
42 from naoqi
import (ALBroker, ALProxy, ALModule)
44 from std_msgs.msg import( String )
45 from std_srvs.srv import( Empty, EmptyResponse )
46 from naoqi_bridge_msgs.msg import(
48 SetSpeechVocabularyGoal,
49 SetSpeechVocabularyResult,
50 SetSpeechVocabularyAction,
51 SpeechWithFeedbackGoal,
52 SpeechWithFeedbackResult,
53 SpeechWithFeedbackFeedback,
54 SpeechWithFeedbackAction )
58 NODE_NAME =
"nao_speech" 59 EVENT =
"WordRecognized" 60 TEXT_STARTED_EVENT =
"ALTextToSpeech/TextStarted" 61 TEXT_DONE_EVENT =
"ALTextToSpeech/TextDone" 68 vocabulary_list = vocabulary.split(
"/")
70 vocabulary_list = [ entry.strip()
for entry
in vocabulary_list]
72 return filter(
None, vocabulary_list)
77 return "ros{}_{}".format(
78 name.replace(
"/",
"_"),
79 rospy.Time.now().to_sec() )
88 class NaoSpeech(ALModule, NaoqiNode):
92 NaoqiNode.__init__(self, Constants.NODE_NAME )
120 self.
sub = rospy.Subscriber(
"speech", String, self.
say )
123 self.
pub = rospy.Publisher(
"word_recognized", WordRecognized )
146 self.setSpeechVocabularyServer.start()
147 self.speechWithFeedbackServer.start()
151 rospy.loginfo(
"Connecting to NaoQi at %s:%d", self.
pip, self.
pport)
154 except RuntimeError,e:
155 print(
"Could not connect to NaoQi's main broker")
162 rospy.logerr(
"Could not get a proxy to ALMemory on %s:%d", self.
pip, self.
pport)
168 rospy.logerr(
"Could not get a proxy to ALTextToSpeech on %s:%d", self.
pip, self.
pport)
172 if self.
audio is None:
175 rospy.logwarn(
"Proxy to ALAudioDevice not available, using dummy device (normal in simulation; volume controls disabled)")
180 self.memProxy.subscribeToEvent(Constants.TEXT_DONE_EVENT, self.
moduleName,
"onTextDone")
181 self.memProxy.subscribeToEvent(Constants.TEXT_STARTED_EVENT, self.
moduleName,
"onTextStarted")
184 self.memProxy.unsubscribeToEvent(Constants.TEXT_DONE_EVENT, self.
moduleName)
185 self.memProxy.unsubscribeToEvent(Constants.TEXT_STARTED_EVENT, self.
moduleName)
194 fb = SpeechWithFeedbackFeedback()
195 self.speechWithFeedbackServer.publish_feedback(fb)
221 self.speechWithFeedbackServer.set_succeeded()
225 rospy.loginfo(
"SetSpeechVocabulary action executing");
232 setVocabularyResult = SetSpeechVocabularyResult()
233 setVocabularyResult.success =
False 234 self.setSpeechVocabularyServer.set_succeeded(setVocabularyResult)
238 for i
in range(0, len(words) - 1):
239 words_str += str(words[i]) +
"/" 241 words_str += words[len(words) - 1]
244 params = {
'vocabulary' : words_str }
245 self.reconf_client.update_configuration(params)
248 setVocabularyResult = SetSpeechVocabularyResult()
249 setVocabularyResult.success =
True 250 self.setSpeechVocabularyServer.set_succeeded(setVocabularyResult)
257 newConf[
"voice"] = request[
"voice"]
258 newConf[
"language"] = request[
"language"]
259 newConf[
"volume"] = request[
"volume"]
260 newConf[
"vocabulary"] = request[
"vocabulary"]
261 newConf[
"audio_expression"] = request[
"audio_expression"]
262 newConf[
"visual_expression"] = request[
"visual_expression"]
263 newConf[
"word_spotting"] = request[
"word_spotting"]
266 if not newConf[
"voice"]:
267 newConf[
"voice"] = self.tts.getVoice()
268 elif newConf[
"voice"]
not in self.tts.getAvailableVoices():
270 "Unknown voice '{}'. Using current voice instead".format(
272 rospy.loginfo(
"Voices available: {}".format(
273 self.tts.getAvailableVoices()))
274 newConf[
"voice"] = self.tts.getVoice()
276 if not newConf[
"language"]:
277 newConf[
"language"] = self.tts.getLanguage()
278 elif newConf[
"language"]
not in self.tts.getAvailableLanguages():
279 newConf[
"language"] = self.tts.getLanguage()
281 "Unknown language '{}'. Using current language instead".format(
282 newConf[
"language"] ) )
283 rospy.loginfo(
"Languages available: {}".format(
284 self.tts.getAvailableLanguages()))
287 if not self.
conf and not rospy.has_param(
"~volume"):
288 newConf[
"volume"] = self.audio.getOutputVolume()
291 if self.
srw and not Util.parse_vocabulary(newConf[
"vocabulary"]):
292 rospy.logwarn(
"Empty vocabulary. Using current vocabulary instead")
293 newConf[
"vocabulary"] = self.
conf[
"vocabulary"]
296 if self.
srw and self.
conf and (
297 newConf[
"language"] != self.
conf[
"language"]
or 298 newConf[
"vocabulary"] != self.
conf[
"language"]
or 299 newConf[
"audio_expression"] != self.
conf[
"audio_expression"]
or 300 newConf[
"visual_expression"] != self.
conf[
"visual_expression"]
or 301 newConf[
"word_spotting"] != self.
conf[
"word_spotting"] ):
302 need_to_restart_speech =
True 304 need_to_restart_speech =
False 309 if need_to_restart_speech:
324 current_voice = self.tts.getVoice()
325 current_language = self.tts.getLanguage()
326 current_volume = self.audio.getOutputVolume()
327 current_gain = self.tts.getVolume()
331 if self.
conf[
"voice"] != current_voice:
332 self.tts.setVoice( self.
conf[
"voice"] )
334 if self.
conf[
"language"] != current_language:
335 self.tts.setLanguage( self.
conf[
"language"] )
337 if self.
conf[
"volume"] != current_volume:
338 self.audio.setOutputVolume( self.
conf[
"volume"] )
340 if target_gain != current_gain:
341 self.tts.setVolume(target_gain)
344 self.tts.say( sentence )
347 if self.
conf[
"voice"] != current_voice:
348 self.tts.setVoice( current_voice )
350 if self.
conf[
"language"] != current_language:
351 self.tts.setLanguage( current_language )
353 if self.
conf[
"volume"] != current_volume:
354 self.audio.setOutputVolume( current_volume )
356 if target_gain != current_gain:
357 self.tts.setVolume(current_gain)
362 rospy.logwarn(
"Speech recognition already started. Restarting.")
365 if Util.parse_vocabulary( self.
conf[
"vocabulary"] ):
372 rospy.logwarn(
"Empty vocabulary. Ignoring request.")
374 return EmptyResponse()
376 def stop( self, request = None ):
378 rospy.logerr(
"Speech recognition was not started")
383 return EmptyResponse()
398 """ROS wrapper for Naoqi speech recognition""" 418 self.
proxy = ALProxy(
"ALSpeechRecognition")
427 subscribers = self.memory.getSubscribers(Constants.EVENT)
429 rospy.logwarn(
"Speech recognition already in use by another node")
430 for module
in subscribers:
437 rospy.loginfo(
"Subscribing '{}' to NAO speech recognition".format(
439 self.memory.subscribeToEvent(
442 self.on_word_recognised.func_name )
448 globals()[
"memory"] = self.
memory 452 self.proxy.setLanguage( config[
"language"] )
453 self.proxy.setAudioExpression( config[
"audio_expression"] )
454 self.proxy.setVisualExpression( config[
"visual_expression"] )
455 self.proxy.setVocabulary(
456 Util.parse_vocabulary( config[
"vocabulary"].encode(
'utf-8') ),
457 config[
"word_spotting"] )
464 rospy.loginfo(
"Unsubscribing '{}' from NAO speech recognition".format(
467 self.memory.unsubscribeToEvent( Constants.EVENT, module )
469 rospy.logwarn(
"Could not unsubscribe from NAO speech recognition")
473 """Publish the words recognized by NAO via ROS """ 476 temp_dict = dict( value[i:i+2]
for i
in range(0, len(value), 2) )
482 self.pub.publish(WordRecognized( temp_dict.keys(), temp_dict.values() ))
485 if __name__ ==
'__main__':
488 rospy.loginfo(
"ROSNaoSpeechModule running..." )
492 rospy.loginfo(
"Stopping ROSNaoSpeechModule ...")
494 if ROSNaoSpeechModule.srw:
495 ROSNaoSpeechModule.srw.stop()
497 ROSNaoSpeechModule.shutdown();
498 rospy.loginfo(
"ROSNaoSpeechModule stopped.")
def stop(self, module=None)
def parse_vocabulary(vocabulary)
def onTextStarted(self, strVarName, value, strMessage)
def stop(self, request=None)
def executeSpeechWithFeedbackAction(self, goal)
def reconfigure(self, request, level)
def internalSay(self, sentence)
def __init__(self, ip, port, publisher, config)
setSpeechVocabularyServer
def onTextDone(self, strVarName, value, strMessage)
def getOutputVolume(self)
def reconfigure(self, config)
def install_naoqi_globals(self)
def __init__(self, moduleName)
def start(self, request=None)
def setOutputVolume(self, vol)
def on_word_recognised(self, key, value, subscriber_id)
def executeSpeechVocabularyAction(self, goal)
def get_proxy(self, name, warn=True)
speech_with_feedback_flag