Kitchen.py
Go to the documentation of this file.
00001 
00002 import roslib; roslib.load_manifest('rocon_kitchen')
00003 import rospy
00004 from demo_msgs.msg import *
00005 from std_msgs.msg import String
00006 from .order_handler import *
00007 
00008 
00009 class Kitchen(object):
00010     
00011     def __init__(self):
00012         self.task = {}
00013         self.task_id = 0
00014 
00015         self.pub = {}
00016         r = RequestRobot()
00017         self.pub['status'] = rospy.Publisher('~status',String)
00018         self.pub['request_robot'] = rospy.Publisher('/mrh/request_robot',RequestRobot)
00019         self.pub['request_goto'] = rospy.Publisher('/mrh/request_goto',RequestGoto)
00020         self.pub['release_robot'] = rospy.Publisher('/mrh/release_robot',ReleaseRobot)
00021 
00022         self.sub = {}
00023         self.sub['order'] = rospy.Subscriber('order',Order,self.process_order)
00024 #        self.sub['command'] = rospy.Subscriber('~command',Command,self.processCommand)
00025 
00026         self.sub['response_robot'] = rospy.Subscriber('/mrh/response_robot',ResponseRobot,self.process_response_robot)
00027         self.sub['response_goto'] = rospy.Subscriber('/mrh/response_goto',ResponseGoto,self.process_response_goto)
00028 
00029         # For Kitchen Frontend 
00030         self.pub['list_tasks'] = rospy.Publisher('/kitchen/list_tasks',ListTasks)
00031         self.pub['request_drink'] = rospy.Publisher('/kitchen/request_drink',RequestDrink)
00032         self.sub['response_drink'] = rospy.Subscriber('/kitchen/response_drink',ResponseDrink,self.process_response_drink)
00033 
00034 
00035     def spin(self):
00036         while not rospy.is_shutdown():
00037             tasks = ListTasks()
00038 
00039             for i, tk in self.task.items():
00040                 t = Task()
00041                 t.task_id = tk.task_id
00042                 t.status = tk.front_status
00043                 tasks.tasks.append(t)
00044             self.pub['list_tasks'].publish(tasks)
00045             rospy.sleep(0.5)
00046 
00047     def process_order(self,msg):
00048         self.log('Got order : ' + str(msg))
00049 
00050         #   Start Order Thread
00051         self.task_id = self.task_id + 1
00052         order = OrderHandler(msg.location,msg.beverage,self.task_id,self.pub,self.done)
00053         self.task[self.task_id] = order
00054         order.start()
00055 
00056     def done(self,task_id):
00057 #        self.log("DONE")
00058         del self.task[task_id]
00059 
00060     def process_response_robot(self,msg):
00061         self.task[msg.task_id].process_response_robot(msg)
00062 
00063     def process_response_goto(self,msg):
00064         self.task[msg.task_id].process_response_goto(msg)
00065 
00066     def process_response_drink(self,msg):
00067         self.task[msg.task_id].process_response_drink(msg)
00068 
00069 
00070     def log(self,msg):
00071         self.pub['status'].publish(msg)
00072         rospy.loginfo("Kitchen : " + str(msg))
 All Classes Namespaces Files Functions Variables Typedefs Enumerations


rocon_kitchen
Author(s): Jihoon
autogenerated on Thu Jan 24 2013 13:33:41