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