bookkeeping.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 import roslib; roslib.load_manifest('robot_booking')
00003 import rospy
00004 from threading import Lock
00005 from std_msgs.msg import *
00006 from robot_booking.srv import *
00007 from robot_booking.msg import *
00008 from visualization_msgs.msg import * 
00009 from interactive_marker_client.msg import *
00010 
00011 class Booklist:
00012   def __init__(self):
00013     self.robot_inuse = False
00014     self.robot_inuse_name = "get_robot_status"
00015     self.robot_set_name = "set_robot_status"
00016     self.lock = Lock()
00017 
00018     self.exp_topic = "/experiment_result"
00019     self.exp2_topic="/experiment_info"
00020     self.key_topic = "/keyboard"
00021     self.marker1_topic = "/intent"
00022     self.marker2_topic ="/median_array"
00023     self.intmarker1_topic = "/grasp_locations/update_web"
00024     self.intmarker2_topic = "/gripper_control/update_web"
00025 
00026   def spin(self):
00027     self.checkService = rospy.Service(self.robot_inuse_name, CheckRobot,self.checkRobotStatus)
00028     self.setService = rospy.Service(self.robot_set_name, CheckRobot,self.setRobotStatus)
00029     self.pubExperimentResult = rospy.Publisher(self.exp_topic, ExperimentResult)
00030     self.pubExperimentInfo = rospy.Publisher(self.exp2_topic, ExperimentInfo)
00031     self.pubKey = rospy.Publisher(self.key_topic, Keys)
00032     self.pubMarker1 = rospy.Publisher(self.marker1_topic, Marker)
00033     self.pubMarker2 = rospy.Publisher(self.marker2_topic, MarkerArray)
00034     self.pubIntMarker1 = rospy.Publisher(self.intmarker1_topic, InteractiveMarkerUpdateWeb)
00035     self.pubIntMarker2 = rospy.Publisher(self.intmarker2_topic, InteractiveMarkerUpdateWeb)
00036 
00037     rospy.loginfo('Robot booking Initialized')
00038 
00039     rospy.spin()
00040     rospy.loginfo('byebye')
00041 
00042 
00043   def checkRobotStatus(self,msg):
00044     rospy.loginfo('Checking robot : ' + str(self.robot_inuse))
00045     rv = False
00046     self.lock.acquire()
00047     if self.robot_inuse == True:
00048       rv = False
00049     else:
00050       rv = True
00051     self.lock.release()
00052     return CheckRobotResponse(rv)
00053 
00054   def setRobotStatus(self,msg):
00055     rv = False
00056     self.lock.acquire()
00057     rospy.loginfo('Setting robot flag to ' + str(msg.set))
00058 
00059     if self.robot_inuse == True:
00060       rv = False
00061     else:
00062       rv = True
00063 #    self.robot_inuse = msg.set
00064     self.lock.release()
00065 
00066     return CheckRobotResponse(rv)
00067     
00068       
00069 
00070 if __name__ == "__main__":
00071   try:
00072     rospy.init_node('robot_booking')
00073     node = Booklist()
00074     node.spin() 
00075   except rospy.ROSInterruptException: pass


robot_booking
Author(s): Jihoon Lee
autogenerated on Sat Sep 27 2014 11:55:47