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 PKG='actionlib'
00032 import roslib; roslib.load_manifest(PKG)
00033 import rospy
00034
00035 import sys
00036
00037 from actionlib.action_server import ActionServer
00038 from actionlib.msg import TestAction,TestFeedback,TestResult
00039
00040 class RefServer (ActionServer):
00041
00042 def __init__(self,name):
00043 action_spec=TestAction
00044 ActionServer.__init__(self,name,action_spec,self.goalCallback,self.cancelCallback, False);
00045 self.start()
00046 rospy.loginfo("Creating ActionServer [%s]\n", name);
00047
00048 self.saved_goals=[]
00049
00050 def goalCallback(self,gh):
00051 goal = gh.get_goal();
00052
00053 rospy.loginfo("Got goal %d", int(goal.goal))
00054 if goal.goal == 1:
00055 gh.set_accepted();
00056 gh.set_succeeded(None, "The ref server has succeeded");
00057 elif goal.goal == 2:
00058 gh.set_accepted();
00059 gh.set_aborted(None, "The ref server has aborted");
00060 elif goal.goal == 3:
00061 gh.set_rejected(None, "The ref server has rejected");
00062
00063
00064 elif goal.goal == 4:
00065
00066 self.saved_goals.append(gh);
00067 gh.set_accepted();
00068
00069 elif goal.goal == 5:
00070
00071 gh.set_accepted();
00072 for g in self.saved_goals:
00073 g.set_succeeded();
00074 self.saved_goals = [];
00075 gh.set_succeeded();
00076
00077
00078 elif goal.goal == 6:
00079 gh.set_accepted();
00080 for g in self.saved_goals:
00081 g.set_aborted();
00082 self.saved_goals = [];
00083 gh.set_succeeded();
00084
00085 elif goal.goal == 7:
00086 gh.set_accepted();
00087 n=len(self.saved_goals);
00088 for i,g in enumerate(self.saved_goals):
00089 g.publish_feedback(TestFeedback(n-i));
00090
00091 gh.set_succeeded();
00092
00093 elif goal.goal == 8:
00094 gh.set_accepted();
00095 n=len(self.saved_goals);
00096 for i,g in enumerate(self.saved_goals):
00097 if i % 2 ==0:
00098 g.set_succeeded(TestResult(n-i), "The ref server has succeeded");
00099 else:
00100 g.set_aborted(TestResult(n-i), "The ref server has aborted")
00101 self.saved_goals=[];
00102 gh.set_succeeded();
00103
00104
00105 else:
00106 pass
00107
00108 def cancelCallback(self,gh):
00109 pass
00110
00111 if __name__=="__main__":
00112 rospy.init_node("ref_server");
00113 ref_server = RefServer("reference_action");
00114
00115 rospy.spin();
00116
00117
00118