Go to the documentation of this file.00001
00002
00003 import roslib; roslib.load_manifest('voice_control')
00004 import rospy
00005 from std_msgs.msg import String
00006 from glass_server.msg import TextMessage
00007 from glass_server.srv import RobotConfiguration
00008 import os
00009
00010
00011 class PseudoOryx:
00012 def __init__(self):
00013
00014
00015 self._command_listener = rospy.Subscriber("/oryx/voice_command", String, self.voiceCommandCallback)
00016
00017
00018 self._text_message_pub = rospy.Publisher("/glass_server/text_messages", TextMessage)
00019
00020 rospy.wait_for_service('robot_configuration')
00021 success = False
00022 try:
00023 self._robot_configuration_srv = rospy.ServiceProxy('robot_configuration', RobotConfiguration)
00024 name = "Oryx"
00025 info = "Planetary exploration mobility platform equiped with three cameras and a scoop"
00026 this_dir = os.path.dirname(__file__)
00027 filename = os.path.join(this_dir, 'oryx_vocab2.xml')
00028 vocab_file = open(filename, "r")
00029 vocab = vocab_file.read()
00030 rospy.loginfo("Sending configuration")
00031 success = self._robot_configuration_srv(name, info, vocab)
00032 vocab_file.close()
00033 rospy.loginfo("Configuration sent")
00034 except rospy.ServiceException, e:
00035 print "Service call failed: %s"%e
00036
00037 if not success:
00038 rospy.loginfo("Configuration unsuccessful")
00039 exit()
00040 rospy.loginfo("Configuration successful")
00041
00042 self.sendTextMessage("Oryx is online\nSystems are ready\nAwaiting commands")
00043
00044
00045 def voiceCommandCallback(self, msg):
00046 rospy.loginfo("Pseudo Oryx received command: " + msg.data)
00047 self.sendTextMessage("I received your command: " + msg.data)
00048
00049 def sendTextMessage(self, text):
00050 rospy.loginfo("Sending text message")
00051 msg = TextMessage()
00052 msg.sender = "Oryx"
00053 msg.text = text
00054 msg.priority = 0
00055
00056 self._text_message_pub.publish(msg)
00057
00058
00059 if __name__=="__main__":
00060 try:
00061 rospy.init_node('pseudo_oryx')
00062 PseudoOryx()
00063 rospy.spin()
00064 except rospy.ROSInterruptException:
00065 rospy.loginfo("Oryx going offline")