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 import roslib; roslib.load_manifest('actionlib')
00030
00031 import sys
00032 import time
00033 import rospy
00034 import rostest
00035
00036 from actionlib.simple_action_server import SimpleActionServer
00037 from actionlib.server_goal_handle import ServerGoalHandle;
00038 from actionlib.msg import *
00039
00040 class RefSimpleServer(SimpleActionServer):
00041
00042 def __init__(self, name):
00043 SimpleActionServer.__init__(self, name, TestRequestAction, self.execute_cb, False)
00044 self.start()
00045
00046 def execute_cb(self, goal):
00047 rospy.logdebug("Goal:\n" + str(goal))
00048 result = TestRequestResult(goal.the_result, True)
00049
00050 if goal.pause_status > rospy.Duration(0.0):
00051 rospy.loginfo("Locking the action server for %.3f seconds" % goal.pause_status.to_sec())
00052 status_continue_time = rospy.get_rostime() + goal.pause_status
00053
00054
00055 with self.action_server.lock:
00056 while rospy.get_rostime() < status_continue_time:
00057 time.sleep(0.02)
00058 rospy.loginfo("Unlocking the action server")
00059
00060
00061 terminate_time = rospy.get_rostime() + goal.delay_terminate
00062 while rospy.get_rostime() < terminate_time:
00063 time.sleep(0.02)
00064 if not goal.ignore_cancel:
00065 if self.is_preempt_requested():
00066 self.set_preempted(result, goal.result_text)
00067 return
00068
00069 rospy.logdebug("Terminating goal as: %i" % goal.terminate_status)
00070
00071 if goal.terminate_status == TestRequestGoal.TERMINATE_SUCCESS:
00072 self.set_succeeded(result, goal.result_text)
00073 elif goal.terminate_status == TestRequestGoal.TERMINATE_ABORTED:
00074 self.set_aborted(result, goal.result_text)
00075 elif goal.terminate_status == TestRequestGoal.TERMINATE_REJECTED:
00076 rospy.logerr("Simple action server cannot reject goals")
00077 self.set_aborted(None, "Simple action server cannot reject goals")
00078 elif goal.terminate_status == TestRequestGoal.TERMINATE_DROP:
00079 rospy.loginfo("About to drop the goal. This should produce an error message.")
00080 return
00081 elif goal.terminate_status == TestRequestGoal.TERMINATE_EXCEPTION:
00082 rospy.loginfo("About to throw an exception. This should produce an error message.")
00083 raise Exception("Terminating by throwing an exception")
00084 elif goal.terminate_status == TestRequestGoal.TERMINATE_LOSE:
00085
00086 for i, s in enumerate(self.action_server.status_list):
00087 if s.status.goal_id.id == self.current_goal.goal.goal_id.id:
00088 del self.action_server.status_list[i]
00089 break
00090 self.current_goal = ServerGoalHandle()
00091 else:
00092 rospy.logerr("Don't know how to terminate as %d" % goal.terminate_status)
00093 self.set_aborted(None, "Don't know how to terminate as %d" % goal.terminate_status)
00094
00095
00096
00097 if __name__ == '__main__':
00098 rospy.init_node("ref_simple_server")
00099 ref_server = RefSimpleServer("test_request_action")
00100 print "Spinning"
00101 rospy.spin()