35 from actionlib.msg
import TestRequestAction, TestRequestGoal, TestRequestResult
40 SimpleActionServer.__init__(self, name, TestRequestAction, self.
execute_cb,
False)
44 rospy.logdebug(
"Goal:\n" + str(goal))
45 result = TestRequestResult(goal.the_result,
True)
47 if goal.pause_status > rospy.Duration(0.0):
48 rospy.loginfo(
"Locking the action server for %.3f seconds" % goal.pause_status.to_sec())
49 status_continue_time = rospy.get_rostime() + goal.pause_status
53 while rospy.get_rostime() < status_continue_time:
55 rospy.loginfo(
"Unlocking the action server")
57 terminate_time = rospy.get_rostime() + goal.delay_terminate
58 while rospy.get_rostime() < terminate_time:
60 if not goal.ignore_cancel:
65 rospy.logdebug(
"Terminating goal as: %i" % goal.terminate_status)
67 if goal.terminate_status == TestRequestGoal.TERMINATE_SUCCESS:
69 elif goal.terminate_status == TestRequestGoal.TERMINATE_ABORTED:
71 elif goal.terminate_status == TestRequestGoal.TERMINATE_REJECTED:
72 rospy.logerr(
"Simple action server cannot reject goals")
73 self.
set_aborted(
None,
"Simple action server cannot reject goals")
74 elif goal.terminate_status == TestRequestGoal.TERMINATE_DROP:
75 rospy.loginfo(
"About to drop the goal. This should produce an error message.")
77 elif goal.terminate_status == TestRequestGoal.TERMINATE_EXCEPTION:
78 rospy.loginfo(
"About to throw an exception. This should produce an error message.")
79 raise Exception(
"Terminating by throwing an exception")
80 elif goal.terminate_status == TestRequestGoal.TERMINATE_LOSE:
83 if s.status.goal_id.id == self.
current_goal.goal.goal_id.id:
88 rospy.logerr(
"Don't know how to terminate as %d" % goal.terminate_status)
89 self.
set_aborted(
None,
"Don't know how to terminate as %d" % goal.terminate_status)
92 if __name__ ==
'__main__':
93 rospy.init_node(
"ref_simple_server")