pseudo_anna.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
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.msg import ImageMessage
00008 from glass_server.srv import RobotConfiguration
00009 from sensor_msgs.msg import Image
00010 from PIL import Image as PyImage
00011 import base64
00012 
00013 import os
00014 
00015 
00016 class PseudoAnna:
00017     def __init__(self):
00018 
00019         #Subscribers
00020         self._command_listener = rospy.Subscriber("/wheelchair/voice_command", String, self.voiceCommandCallback)
00021 
00022         #Publishers
00023         self._text_message_pub = rospy.Publisher("/glass_server/text_messages", TextMessage)
00024         self._image_message_pub = rospy.Publisher("/glass_server/image_messages", ImageMessage)
00025 
00026         rospy.wait_for_service('robot_configuration')
00027         success = False
00028         try:
00029             self._robot_configuration_srv = rospy.ServiceProxy('robot_configuration', RobotConfiguration)
00030             name = "Wheelchair"
00031             info = "Voice controlled semi-autonomous wheelchair"
00032             this_dir = os.path.dirname(__file__)
00033             filename = os.path.join(this_dir, 'anna_vocab.xml')
00034             vocab_file = open(filename, "r")
00035             vocab = vocab_file.read()
00036             rospy.loginfo("Sending configuration")
00037             success = self._robot_configuration_srv(name, info, vocab)
00038             vocab_file.close()
00039             rospy.loginfo("Configuration sent")
00040         except rospy.ServiceException, e:
00041             print "Service call failed: %s"%e
00042 
00043         if not success:
00044             rospy.loginfo("Configuration unsuccessful")
00045             exit()
00046         rospy.loginfo("Configuration successful")
00047 
00048         self.sendTextMessage("Hello Google Glass!")
00049 
00050         this_dir = os.path.dirname(__file__)
00051         filename = os.path.join(this_dir, 'anna_pic.jpg')
00052         image_file = open(filename, "rb")
00053         image_str = base64.b64encode(image_file.read())
00054         self.sendImageMessage("Here is a picture of me!", image_str)
00055 
00056 
00057     def voiceCommandCallback(self, msg):
00058         rospy.loginfo("Pseudo Anna received command: " + msg.data)
00059         self.sendTextMessage("I received your command: " + msg.data)
00060 
00061     def sendTextMessage(self, text):
00062         rospy.loginfo("Sending text message")
00063         msg = TextMessage()
00064         msg.sender = "Wheelchair"
00065         msg.text = text
00066         msg.priority = 0
00067 
00068         self._text_message_pub.publish(msg)
00069 
00070     def sendImageMessage(self, text, image_str):
00071         rospy.loginfo("Sending image message")
00072         msg = ImageMessage()
00073         msg.sender = "Wheelchair"
00074         msg.text = text
00075         msg.base64_image = image_str
00076         msg.priority = 0
00077 
00078         self._image_message_pub.publish(msg)
00079 
00080 
00081 if __name__=="__main__":
00082     try:
00083         rospy.init_node('pseudo_anna')
00084         PseudoAnna()
00085         rospy.spin()
00086     except rospy.ROSInterruptException:
00087         rospy.loginfo("Anna going offline")


google_glass_driver
Author(s): Nicholas Otero
autogenerated on Fri Aug 28 2015 10:51:44