Go to the documentation of this file.00001
00002
00003
00004 import roslib;
00005 roslib.load_manifest('nao_vision')
00006 import rospy
00007 from std_msgs.msg import String
00008 from std_msgs.msg import Float32
00009 import sys
00010
00011
00012 path = rospy.get_param("/naoqi/path", "")
00013 sys.path.append(path)
00014
00015
00016 try:
00017 from naoqi import ALProxy
00018 except ImportError:
00019 rospy.logerr("NAOqi not found - Please check to see if it is in your PYTHONPATH variable.")
00020 exit(1)
00021
00022 class NaoSpeech():
00023 def __init__(self):
00024 rospy.init_node("nao_speech")
00025
00026
00027 try:
00028 host = rospy.get_param("/naoqi/host")
00029 except KeyError:
00030 rospy.logerr("Unable to find parameter /naoqi/host")
00031 exit(1)
00032 try:
00033 port = rospy.get_param("/naoqi/port")
00034 except KeyError:
00035 rospy.logerr("Unable to find parameter /naoqi/port")
00036 exit(1)
00037
00038
00039 try:
00040 self.tts = ALProxy("ALTextToSpeech", host, port)
00041 except Exception:
00042 rospy.logerr("Unable to create speech proxy.")
00043 exit(1)
00044
00045
00046 volume = rospy.get_param("~volume", 0.5)
00047 lang = rospy.get_param("~language", "English")
00048
00049
00050 self.tts.post.setLanguage(lang)
00051 self.tts.post.setVolume(volume)
00052 rospy.Subscriber("nao_say", String, self.nao_say_callback)
00053 rospy.Subscriber("nao_set_volume", Float32, self.nao_set_volume_callback)
00054 rospy.Subscriber("nao_set_lang", String, self.nao_set_lang_callback)
00055
00056 rospy.loginfo("NAO Speech Node Initialized")
00057
00058 def nao_say_callback(self, data):
00059 self.tts.post.say(data.data)
00060
00061 def nao_set_volume_callback(self, data):
00062 self.tts.post.setVolume(data.data)
00063
00064 def nao_set_lang_callback(self, data):
00065 self.tts.post.setLanguage(data.data)
00066
00067 if __name__ == '__main__':
00068 NaoSpeech = NaoSpeech()
00069 rospy.spin()