ref_simple_server.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Copyright (c) 2009, Willow Garage, Inc.
3 # All rights reserved.
4 #
5 # Redistribution and use in source and binary forms, with or without
6 # modification, are permitted provided that the following conditions are met:
7 #
8 # * Redistributions of source code must retain the above copyright
9 # notice, this list of conditions and the following disclaimer.
10 # * Redistributions in binary form must reproduce the above copyright
11 # notice, this list of conditions and the following disclaimer in the
12 # documentation and/or other materials provided with the distribution.
13 # * Neither the name of the Willow Garage, Inc. nor the names of its
14 # contributors may be used to endorse or promote products derived from
15 # this software without specific prior written permission.
16 #
17 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 # POSSIBILITY OF SUCH DAMAGE.
28 
29 # Author: Alexander Sorokin.
30 # Based on code from ref_server.cpp by Vijay Pradeep
31 PKG='actionlib'
32 import roslib; roslib.load_manifest(PKG)
33 import rospy
34 
35 import sys
36 
37 from actionlib.simple_action_server import SimpleActionServer
38 from actionlib.msg import TestAction,TestFeedback
39 
40 
42 
43  def __init__(self,name):
44  action_spec=TestAction
45  SimpleActionServer.__init__(self,name,action_spec,self.goal_callback, False);
46  self.start()
47  rospy.loginfo("Creating SimpleActionServer [%s]\n", name);
48 
49 
50  def goal_callback(self,goal):
51 
52  rospy.loginfo("Got goal %d", int(goal.goal))
53  if goal.goal == 1:
54  self.set_succeeded(None, "The ref server has succeeded");
55  elif goal.goal == 2:
56  self.set_aborted(None, "The ref server has aborted");
57 
58  elif goal.goal == 3:
59  self.set_aborted(None, "The simple action server can't reject goals");
60 
61 
62  elif goal.goal == 4:
63  self.set_aborted(None, "Simple server can't save goals");
64 
65 
66  elif goal.goal == 5:
67  self.set_aborted(None, "Simple server can't save goals");
68 
69  elif goal.goal == 6:
70  self.set_aborted(None, "Simple server can't save goals");
71 
72 
73 
74  elif goal.goal == 7:
75  self.set_aborted(None, "Simple server can't save goals");
76 
77  elif goal.goal == 8:
78  self.set_aborted(None, "Simple server can't save goals");
79 
80  elif goal.goal == 9:
81  rospy.sleep(1);
82  rospy.loginfo("Sending feedback")
83  self.publish_feedback(TestFeedback(9)); #by the goal ID
84  rospy.sleep(1);
85  self.set_succeeded(None, "The ref server has succeeded");
86 
87 
88  else:
89  pass
90 
91 if __name__=="__main__":
92  rospy.init_node("ref_simple_server");
93  ref_server = RefSimpleServer("reference_simple_action");
94 
95  rospy.spin();
96 
97 
98 


roseus
Author(s): Kei Okada
autogenerated on Fri Mar 26 2021 02:08:16