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 rospy
33 
34 from actionlib.simple_action_server import SimpleActionServer
35 from actionlib.msg import TestAction, TestFeedback
36 
37 
39 
40  def __init__(self, name):
41  action_spec = TestAction
42  SimpleActionServer.__init__(
43  self, name, action_spec, self.goal_callback, False)
44  self.start()
45  rospy.loginfo("Creating SimpleActionServer [%s]\n", name)
46 
47  def goal_callback(self, goal):
48  rospy.loginfo("Got goal %d", int(goal.goal))
49  if goal.goal == 1:
50  self.set_succeeded(None, "The ref server has succeeded")
51  elif goal.goal == 2:
52  self.set_aborted(None, "The ref server has aborted")
53  elif goal.goal == 3:
54  self.set_aborted(None, "The simple action server can't reject goals")
55  elif goal.goal == 4:
56  self.set_aborted(None, "Simple server can't save goals")
57  elif goal.goal == 5:
58  self.set_aborted(None, "Simple server can't save goals")
59  elif goal.goal == 6:
60  self.set_aborted(None, "Simple server can't save goals")
61  elif goal.goal == 7:
62  self.set_aborted(None, "Simple server can't save goals")
63  elif goal.goal == 8:
64  self.set_aborted(None, "Simple server can't save goals")
65  elif goal.goal == 9:
66  rospy.sleep(1)
67  rospy.loginfo("Sending feedback")
68  self.publish_feedback(TestFeedback(9)) # by the goal ID
69  rospy.sleep(1)
70  self.set_succeeded(None, "The ref server has succeeded")
71  else:
72  pass
73 
74 
75 if __name__ == "__main__":
76  rospy.init_node("ref_simple_server")
77  ref_server = RefSimpleServer("reference_simple_action")
78 
79  rospy.spin()
def set_aborted(self, result=None, text="")
Sets the status of the active goal to aborted.
def publish_feedback(self, feedback)
Publishes feedback for a given goal.
def set_succeeded(self, result=None, text="")
Sets the status of the active goal to succeeded.
def start(self)
Explicitly start the action server, used it auto_start is set to false.
The SimpleActionServer implements a singe goal policy on top of the ActionServer class.


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Mon Feb 18 2019 03:59:59