ref_server.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Copyright (c) 2009, Willow Garage, Inc.
00003 # All rights reserved.
00004 # 
00005 # Redistribution and use in source and binary forms, with or without
00006 # modification, are permitted provided that the following conditions are met:
00007 # 
00008 #     * Redistributions of source code must retain the above copyright
00009 #       notice, this list of conditions and the following disclaimer.
00010 #     * Redistributions in binary form must reproduce the above copyright
00011 #       notice, this list of conditions and the following disclaimer in the
00012 #       documentation and/or other materials provided with the distribution.
00013 #     * Neither the name of the Willow Garage, Inc. nor the names of its
00014 #       contributors may be used to endorse or promote products derived from
00015 #       this software without specific prior written permission.
00016 # 
00017 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027 # POSSIBILITY OF SUCH DAMAGE.
00028 
00029 # Author: Alexander Sorokin. 
00030 # Based on code from ref_server.cpp by Vijay Pradeep
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 


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep
autogenerated on Sun Oct 5 2014 22:02:55