simple_action_server.py
Go to the documentation of this file.
1 # Copyright (c) 2009, Willow Garage, Inc.
2 # All rights reserved.
3 #
4 # Redistribution and use in source and binary forms, with or without
5 # modification, are permitted provided that the following conditions are met:
6 #
7 # * Redistributions of source code must retain the above copyright
8 # notice, this list of conditions and the following disclaimer.
9 # * Redistributions in binary form must reproduce the above copyright
10 # notice, this list of conditions and the following disclaimer in the
11 # documentation and/or other materials provided with the distribution.
12 # * Neither the name of the Willow Garage, Inc. nor the names of its
13 # contributors may be used to endorse or promote products derived from
14 # this software without specific prior written permission.
15 #
16 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 # POSSIBILITY OF SUCH DAMAGE.
27 #
28 # Author: Alexander Sorokin.
29 # Based on C++ simple_action_server.h by Eitan Marder-Eppstein
30 import rospy
31 import threading
32 import traceback
33 
34 from actionlib_msgs.msg import GoalStatus
35 
36 from actionlib import ActionServer
37 from actionlib.server_goal_handle import ServerGoalHandle
38 
39 
40 def nop_cb(goal_handle):
41  pass
42 
43 
44 
55 
61  def __init__(self, name, ActionSpec, execute_cb=None, auto_start=True):
62 
63  self.new_goal = False
64  self.preempt_request = False
66 
67  self.execute_callback = execute_cb
68  self.goal_callback = None
69  self.preempt_callback = None
70 
71  self.need_to_terminate = False
72  self.terminate_mutex = threading.RLock()
73 
74  # since the internal_goal/preempt_callbacks are invoked from the
75  # ActionServer while holding the self.action_server.lock
76  # self.lock must always be locked after the action server lock
77  # to avoid an inconsistent lock acquisition order
78  self.lock = threading.RLock()
79 
80  self.execute_condition = threading.Condition(self.lock)
81 
84 
85  if self.execute_callback:
86  self.execute_thread = threading.Thread(None, self.executeLoop)
87  self.execute_thread.start()
88  else:
89  self.execute_thread = None
90 
91  # create the action server
92  self.action_server = ActionServer(name, ActionSpec, self.internal_goal_callback, self.internal_preempt_callback, auto_start)
93 
94  def __del__(self):
95  if hasattr(self, 'execute_callback') and self.execute_callback:
96  with self.terminate_mutex:
97  self.need_to_terminate = True
98 
99  assert(self.execute_thread)
100  self.execute_thread.join()
101 
102 
111  def accept_new_goal(self):
112  with self.action_server.lock, self.lock:
113  if not self.new_goal or not self.next_goal.get_goal():
114  rospy.logerr("Attempting to accept the next goal when a new goal is not available")
115  return None
116 
117  # check if we need to send a preempted message for the goal that we're currently pursuing
118  if self.is_active() and self.current_goal.get_goal() and self.current_goal != self.next_goal:
119  self.current_goal.set_canceled(None, "This goal was canceled because another goal was received by the simple action server")
120 
121  rospy.logdebug("Accepting a new goal")
122 
123  # accept the next goal
124  self.current_goal = self.next_goal
125  self.new_goal = False
126 
127  # set preempt to request to equal the preempt state of the new goal
129  self.new_goal_preempt_request = False
130 
131  # set the status of the current goal to be active
132  self.current_goal.set_accepted("This goal has been accepted by the simple action server")
133 
134  return self.current_goal.get_goal()
135 
136 
139  return self.new_goal
140 
141 
144  return self.preempt_request
145 
146 
148  def is_active(self):
149  if not self.current_goal.get_goal():
150  return False
151 
152  status = self.current_goal.get_goal_status().status
153  return status == GoalStatus.ACTIVE or status == GoalStatus.PREEMPTING
154 
155 
157  def set_succeeded(self, result=None, text=""):
158  with self.action_server.lock, self.lock:
159  if not result:
160  result = self.get_default_result()
161  self.current_goal.set_succeeded(result, text)
162 
163 
165  def set_aborted(self, result=None, text=""):
166  with self.action_server.lock, self.lock:
167  if not result:
168  result = self.get_default_result()
169  self.current_goal.set_aborted(result, text)
170 
171 
173  def publish_feedback(self, feedback):
174  self.current_goal.publish_feedback(feedback)
175 
177  return self.action_server.ActionResultType()
178 
179 
181  def set_preempted(self, result=None, text=""):
182  if not result:
183  result = self.get_default_result()
184  with self.action_server.lock, self.lock:
185  rospy.logdebug("Setting the current goal as canceled")
186  self.current_goal.set_canceled(result, text)
187 
188 
190  def register_goal_callback(self, cb):
191  if self.execute_callback:
192  rospy.logwarn("Cannot call SimpleActionServer.register_goal_callback() because an executeCallback exists. Not going to register it.")
193  else:
194  self.goal_callback = cb
195 
196 
199  self.preempt_callback = cb
200 
201 
202  def start(self):
203  self.action_server.start()
204 
205 
206  def internal_goal_callback(self, goal):
207  self.execute_condition.acquire()
208 
209  try:
210  rospy.logdebug("A new goal %s has been received by the single goal action server", goal.get_goal_id().id)
211 
212  # check that the timestamp is past that of the current goal and the next goal
213  if((not self.current_goal.get_goal() or goal.get_goal_id().stamp >= self.current_goal.get_goal_id().stamp)
214  and (not self.next_goal.get_goal() or goal.get_goal_id().stamp >= self.next_goal.get_goal_id().stamp)):
215  # if next_goal has not been accepted already... its going to get bumped, but we need to let the client know we're preempting
216  if(self.next_goal.get_goal() and (not self.current_goal.get_goal() or self.next_goal != self.current_goal)):
217  self.next_goal.set_canceled(None, "This goal was canceled because another goal was received by the simple action server")
218 
219  self.next_goal = goal
220  self.new_goal = True
221  self.new_goal_preempt_request = False
222 
223  # if the server is active, we'll want to call the preempt callback for the current goal
224  if(self.is_active()):
225  self.preempt_request = True
226  # if the user has registered a preempt callback, we'll call it now
227  if(self.preempt_callback):
228  self.preempt_callback()
229 
230  # if the user has defined a goal callback, we'll call it now
231  if self.goal_callback:
232  self.goal_callback()
233 
234  # Trigger runLoop to call execute()
235  self.execute_condition.notify()
236  self.execute_condition.release()
237  else:
238  # the goal requested has already been preempted by a different goal, so we're not going to execute it
239  goal.set_canceled(None, "This goal was canceled because another goal was received by the simple action server")
240  self.execute_condition.release()
241  except Exception as e:
242  rospy.logerr("SimpleActionServer.internal_goal_callback - exception %s", str(e))
243  self.execute_condition.release()
244 
245 
246  def internal_preempt_callback(self, preempt):
247  with self.lock:
248  rospy.logdebug("A preempt has been received by the SimpleActionServer")
249 
250  # if the preempt is for the current goal, then we'll set the preemptRequest flag and call the user's preempt callback
251  if(preempt == self.current_goal):
252  rospy.logdebug("Setting preempt_request bit for the current goal to TRUE and invoking callback")
253  self.preempt_request = True
254 
255  # if the user has registered a preempt callback, we'll call it now
256  if(self.preempt_callback):
257  self.preempt_callback()
258  # if the preempt applies to the next goal, we'll set the preempt bit for that
259  elif(preempt == self.next_goal):
260  rospy.logdebug("Setting preempt request bit for the next goal to TRUE")
261  self.new_goal_preempt_request = True
262 
263 
264  def executeLoop(self):
265  loop_duration = rospy.Duration.from_sec(.1)
266 
267  while (not rospy.is_shutdown()):
268  with self.terminate_mutex:
269  if (self.need_to_terminate):
270  break
271 
272  # the following checks (is_active, is_new_goal_available)
273  # are performed without locking
274  # the worst thing that might happen in case of a race
275  # condition is a warning/error message on the console
276  if (self.is_active()):
277  rospy.logerr("Should never reach this code with an active goal")
278  return
279 
280  if (self.is_new_goal_available()):
281  # accept_new_goal() is performing its own locking
282  goal = self.accept_new_goal()
283  if not self.execute_callback:
284  rospy.logerr("execute_callback_ must exist. This is a bug in SimpleActionServer")
285  return
286 
287  try:
288  self.execute_callback(goal)
289 
290  if self.is_active():
291  rospy.logwarn("Your executeCallback did not set the goal to a terminal status. " +
292  "This is a bug in your ActionServer implementation. Fix your code! " +
293  "For now, the ActionServer will set this goal to aborted")
294  self.set_aborted(None, "No terminal state was set.")
295  except Exception as ex:
296  rospy.logerr("Exception in your execute callback: %s\n%s", str(ex),
297  traceback.format_exc())
298  self.set_aborted(None, "Exception in execute callback: %s" % str(ex))
299 
300  with self.execute_condition:
301  self.execute_condition.wait(loop_duration.to_sec())
actionlib.simple_action_server.SimpleActionServer.register_goal_callback
def register_goal_callback(self, cb)
Allows users to register a callback to be invoked when a new goal is available.
Definition: simple_action_server.py:190
actionlib.simple_action_server.nop_cb
def nop_cb(goal_handle)
Definition: simple_action_server.py:40
actionlib.simple_action_server.SimpleActionServer.execute_thread
execute_thread
Definition: simple_action_server.py:86
actionlib.simple_action_server.SimpleActionServer.set_succeeded
def set_succeeded(self, result=None, text="")
Sets the status of the active goal to succeeded.
Definition: simple_action_server.py:157
actionlib.server_goal_handle
Definition: server_goal_handle.py:1
actionlib::ActionServer
The ActionServer is a helpful tool for managing goal requests to a node. It allows the user to specif...
Definition: action_server.h:107
actionlib.simple_action_server.SimpleActionServer.set_aborted
def set_aborted(self, result=None, text="")
Sets the status of the active goal to aborted.
Definition: simple_action_server.py:165
actionlib.simple_action_server.SimpleActionServer.current_goal
current_goal
Definition: simple_action_server.py:82
actionlib.simple_action_server.SimpleActionServer.next_goal
next_goal
Definition: simple_action_server.py:83
actionlib.simple_action_server.SimpleActionServer.accept_new_goal
def accept_new_goal(self)
Accepts a new goal when one is available The status of this goal is set to active upon acceptance,...
Definition: simple_action_server.py:111
actionlib.simple_action_server.SimpleActionServer.__del__
def __del__(self)
Definition: simple_action_server.py:94
actionlib.simple_action_server.SimpleActionServer.__init__
def __init__(self, name, ActionSpec, execute_cb=None, auto_start=True)
Constructor for a SimpleActionServer.
Definition: simple_action_server.py:61
actionlib.simple_action_server.SimpleActionServer.start
def start(self)
Explicitly start the action server, used it auto_start is set to false.
Definition: simple_action_server.py:202
actionlib.simple_action_server.SimpleActionServer.register_preempt_callback
def register_preempt_callback(self, cb)
Allows users to register a callback to be invoked when a new preempt request is available.
Definition: simple_action_server.py:198
actionlib.server_goal_handle.ServerGoalHandle
Definition: server_goal_handle.py:35
actionlib.simple_action_server.SimpleActionServer.preempt_request
preempt_request
Definition: simple_action_server.py:64
actionlib.simple_action_server.SimpleActionServer.execute_callback
execute_callback
Definition: simple_action_server.py:67
actionlib.simple_action_server.SimpleActionServer.get_default_result
def get_default_result(self)
Definition: simple_action_server.py:176
actionlib.simple_action_server.SimpleActionServer.preempt_callback
preempt_callback
Definition: simple_action_server.py:69
actionlib.simple_action_server.SimpleActionServer.is_active
def is_active(self)
Allows polling implementations to query about the status of the current goal.
Definition: simple_action_server.py:148
actionlib.simple_action_server.SimpleActionServer.set_preempted
def set_preempted(self, result=None, text="")
Sets the status of the active goal to preempted.
Definition: simple_action_server.py:181
actionlib.simple_action_server.SimpleActionServer.executeLoop
def executeLoop(self)
Called from a separate thread to call blocking execute calls.
Definition: simple_action_server.py:264
actionlib.simple_action_server.SimpleActionServer.is_preempt_requested
def is_preempt_requested(self)
Allows polling implementations to query about preempt requests.
Definition: simple_action_server.py:143
actionlib.simple_action_server.SimpleActionServer.new_goal_preempt_request
new_goal_preempt_request
Definition: simple_action_server.py:65
actionlib.simple_action_server.SimpleActionServer.internal_goal_callback
def internal_goal_callback(self, goal)
Callback for when the ActionServer receives a new goal and passes it on.
Definition: simple_action_server.py:206
actionlib.simple_action_server.SimpleActionServer.goal_callback
goal_callback
Definition: simple_action_server.py:68
actionlib.simple_action_server.SimpleActionServer.publish_feedback
def publish_feedback(self, feedback)
Publishes feedback for a given goal.
Definition: simple_action_server.py:173
actionlib.simple_action_server.SimpleActionServer.execute_condition
execute_condition
Definition: simple_action_server.py:80
actionlib.simple_action_server.SimpleActionServer.is_new_goal_available
def is_new_goal_available(self)
Allows polling implementations to query about the availability of a new goal.
Definition: simple_action_server.py:138
actionlib.simple_action_server.SimpleActionServer
The SimpleActionServer implements a singe goal policy on top of the ActionServer class....
Definition: simple_action_server.py:54
actionlib.simple_action_server.SimpleActionServer.lock
lock
Definition: simple_action_server.py:78
actionlib.simple_action_server.SimpleActionServer.terminate_mutex
terminate_mutex
Definition: simple_action_server.py:72
actionlib.simple_action_server.SimpleActionServer.action_server
action_server
Definition: simple_action_server.py:92
actionlib.simple_action_server.SimpleActionServer.internal_preempt_callback
def internal_preempt_callback(self, preempt)
Callback for when the ActionServer receives a new preempt and passes it on.
Definition: simple_action_server.py:246
actionlib.simple_action_server.SimpleActionServer.need_to_terminate
need_to_terminate
Definition: simple_action_server.py:71
actionlib.simple_action_server.SimpleActionServer.new_goal
new_goal
Definition: simple_action_server.py:63


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Fri May 19 2023 02:36:55