00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 import roslib; roslib.load_manifest('ui_preempter')
00038 import rospy
00039 import actionlib
00040
00041 from application_msgs.msg import ApplicationAction
00042 from std_msgs.msg import Empty
00043
00044 class UIPreempter:
00045 def __init__(self):
00046 self.server = actionlib.SimpleActionServer('action_ns', ApplicationAction, self.execute)
00047 self.preempt_pub = rospy.Publisher(rospy.remap_name('action_ns') + '/preempt_request', Empty, None, False, True)
00048 self.preempt_sub = rospy.Subscriber(rospy.remap_name('action_ns') + '/preempt_response', Empty, self.response_cb)
00049 self.response_heard = False
00050
00051 def execute(self, goal):
00052 rospy.loginfo('Got an application goal')
00053 r = rospy.Rate(10.0)
00054 while not rospy.is_shutdown():
00055 if self.server.is_preempt_requested():
00056 rospy.loginfo('Got a preempt request')
00057 self.preempt_ui_and_wait()
00058 self.server.set_preempted()
00059 return
00060 r.sleep()
00061
00062 def preempt_ui_and_wait(self):
00063
00064 self.response_heard = False
00065
00066
00067 rospy.loginfo('Sending a preempt request to the UI')
00068 self.preempt_pub.publish(Empty())
00069
00070
00071 r = rospy.Rate(10.0)
00072 while not self.response_heard and not rospy.is_shutdown() and self.preempt_sub.get_num_connections() > 0:
00073 r.sleep()
00074
00075 if self.preempt_sub.get_num_connections() == 0:
00076 rospy.loginfo("No one is subscribed to the UI preempter so it'll just shut down")
00077 return
00078
00079 if rospy.is_shutdown():
00080 rospy.loginfo("Getting torn down, but I never got a response from the UI")
00081 else:
00082 rospy.loginfo("The ui for this application has given the OK for the application to be taken down")
00083
00084 def response_cb(self, msg):
00085 self.response_heard = True
00086
00087 if __name__ == '__main__':
00088 rospy.init_node('ui_preempter')
00089 ui_p = UIPreempter()
00090 rospy.spin()