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++ action_server.h by Eitan Marder-Eppstein
30 import rospy
31 import threading
32 
33 from actionlib_msgs.msg import GoalID, GoalStatus, GoalStatusArray
34 
35 from actionlib.goal_id_generator import GoalIDGenerator
36 from actionlib.status_tracker import StatusTracker
37 
38 from actionlib.handle_tracker_deleter import HandleTrackerDeleter
39 from actionlib.server_goal_handle import ServerGoalHandle
40 
41 from actionlib.exceptions import ActionException
42 
43 
44 def nop_cb(goal_handle):
45  pass
46 
47 
48 
57 
63  def __init__(self, ns, ActionSpec, goal_cb, cancel_cb=nop_cb, auto_start=True):
64  self.ns = ns
65 
66  try:
67  a = ActionSpec()
68 
69  self.ActionSpec = ActionSpec
70  self.ActionGoal = type(a.action_goal)
71  self.ActionResult = type(a.action_result)
72  self.ActionResultType = type(a.action_result.result)
73  self.ActionFeedback = type(a.action_feedback)
74  except AttributeError:
75  raise ActionException("Type is not an action spec: %s" % str(ActionSpec))
76 
77  self.goal_sub = None
78  self.cancel_sub = None
79  self.status_pub = None
80  self.result_pub = None
81  self.feedback_pub = None
82 
83  self.lock = threading.RLock()
84 
85  self.status_timer = None
86 
87  self.status_list = []
88 
89  self.last_cancel = rospy.Time()
90  self.status_list_timeout = rospy.Duration()
91 
93 
94  self.goal_callback = goal_cb
95  assert(self.goal_callback)
96 
97  self.cancel_callback = cancel_cb
98  self.auto_start = auto_start
99 
100  self.started = False
101 
102  if self.auto_start:
103  rospy.logwarn("You've passed in true for auto_start to the python action server, you should always pass "
104  "in false to avoid race conditions.")
105  self.start()
106 
107 
109  def register_goal_callback(self, cb):
110  self.goal_callback = cb
111 
112 
114  def register_cancel_callback(self, cancel_cb):
115  self.cancel_callback = cancel_cb
116 
117 
118  def start(self):
119  with self.lock:
120  self.initialize()
121  self.started = True
122  self.publish_status()
123 
124 
125  def stop(self):
126  with self.lock:
127  self.started = False
128  self.status_timer.shutdown()
129  self.goal_sub.unregister()
130  self.cancel_sub.unregister()
131  self.status_pub.unregister()
132  self.feedback_pub.unregister()
133  self.result_pub.unregister()
134 
135 
136  def initialize(self):
137  self.pub_queue_size = rospy.get_param('actionlib_server_pub_queue_size', 50)
138  if self.pub_queue_size < 0:
139  self.pub_queue_size = 50
140  self.status_pub = rospy.Publisher(rospy.remap_name(self.ns)+"/status", GoalStatusArray, latch=True, queue_size=self.pub_queue_size)
141  self.result_pub = rospy.Publisher(rospy.remap_name(self.ns)+"/result", self.ActionResult, queue_size=self.pub_queue_size)
142  self.feedback_pub = rospy.Publisher(rospy.remap_name(self.ns)+"/feedback", self.ActionFeedback, queue_size=self.pub_queue_size)
143 
144  self.sub_queue_size = rospy.get_param('actionlib_server_sub_queue_size', -1)
145  if self.sub_queue_size < 0:
146  self.sub_queue_size = None
147  self.goal_sub = rospy.Subscriber(rospy.remap_name(self.ns)+"/goal", self.ActionGoal, callback=self.internal_goal_callback, queue_size=self.sub_queue_size)
148 
149  self.cancel_sub = rospy.Subscriber(rospy.remap_name(self.ns)+"/cancel", GoalID, callback=self.internal_cancel_callback, queue_size=self.sub_queue_size)
150 
151  # read the frequency with which to publish status from the parameter server
152  # if not specified locally explicitly, use search param to find actionlib_status_frequency
153  resolved_status_frequency_name = rospy.remap_name(self.ns)+"/status_frequency"
154  if rospy.has_param(resolved_status_frequency_name):
155  self.status_frequency = rospy.get_param(resolved_status_frequency_name, 5.0)
156  rospy.logwarn("You're using the deprecated status_frequency parameter, please switch to actionlib_status_frequency.")
157  else:
158  search_status_frequency_name = rospy.search_param("actionlib_status_frequency")
159  if search_status_frequency_name is None:
160  self.status_frequency = 5.0
161  else:
162  self.status_frequency = rospy.get_param(search_status_frequency_name, 5.0)
163 
164  status_list_timeout = rospy.get_param(rospy.remap_name(self.ns)+"/status_list_timeout", 5.0)
165  self.status_list_timeout = rospy.Duration(status_list_timeout)
166 
167  if self.status_frequency > 0.0:
168  status_period = rospy.Duration(1.0 / self.status_frequency)
169  self.status_timer = rospy.Timer(status_period, self.publish_status_async)
170 
171 
174  def publish_result(self, status, result):
175  with self.lock:
176  ar = self.ActionResult()
177  ar.header.stamp = rospy.Time.now()
178  ar.status = status
179  ar.result = result
180  if not rospy.is_shutdown():
181  self.result_pub.publish(ar)
182  self.publish_status()
183 
184 
187  def publish_feedback(self, status, feedback):
188  with self.lock:
189  af = self.ActionFeedback()
190  af.header.stamp = rospy.Time.now()
191  af.status = status
192  af.feedback = feedback
193  if not rospy.is_shutdown():
194  self.feedback_pub.publish(af)
195 
196 
197  def internal_cancel_callback(self, goal_id):
198  with self.lock:
199 
200  # if we're not started... then we're not actually going to do anything
201  if not self.started:
202  return
203 
204  # we need to handle a cancel for the user
205  rospy.logdebug("The action server has received a new cancel request")
206 
207  goal_id_found = False
208  for st in self.status_list[:]:
209  # check if the goal id is zero or if it is equal to the goal id of
210  # the iterator or if the time of the iterator warrants a cancel
211 
212  cancel_everything = (goal_id.id == "" and goal_id.stamp == rospy.Time()) # rospy::Time()) #id and stamp 0 --> cancel everything
213  cancel_this_one = (goal_id.id == st.status.goal_id.id) # ids match... cancel that goal
214  cancel_before_stamp = (goal_id.stamp != rospy.Time() and st.status.goal_id.stamp <= goal_id.stamp) # //stamp != 0 --> cancel everything before stamp
215 
216  if cancel_everything or cancel_this_one or cancel_before_stamp:
217  # we need to check if we need to store this cancel request for later
218  if goal_id.id == st.status.goal_id.id:
219  goal_id_found = True
220 
221  # attempt to get the handle_tracker for the list item if it exists
222  handle_tracker = st.handle_tracker
223 
224  if handle_tracker is None:
225  # if the handle tracker is expired, then we need to create a new one
226  handle_tracker = HandleTrackerDeleter(self, st)
227  st.handle_tracker = handle_tracker
228 
229  # we also need to reset the time that the status is supposed to be removed from the list
230  st.handle_destruction_time = rospy.Time.now()
231 
232  # set the status of the goal to PREEMPTING or RECALLING as appropriate
233  # and check if the request should be passed on to the user
234  gh = ServerGoalHandle(st, self, handle_tracker)
235  if gh.set_cancel_requested():
236  # call the user's cancel callback on the relevant goal
237  self.cancel_callback(gh)
238 
239  # if the requested goal_id was not found, and it is non-zero, then we need to store the cancel request
240  if goal_id.id != "" and not goal_id_found:
241  tracker = StatusTracker(goal_id, GoalStatus.RECALLING)
242  self.status_list.append(tracker)
243  # start the timer for how long the status will live in the list without a goal handle to it
244  tracker.handle_destruction_time = rospy.Time.now()
245 
246  # make sure to set last_cancel_ based on the stamp associated with this cancel request
247  if goal_id.stamp > self.last_cancel:
248  self.last_cancel = goal_id.stamp
249 
250 
251  def internal_goal_callback(self, goal):
252  with self.lock:
253  # if we're not started... then we're not actually going to do anything
254  if not self.started:
255  return
256 
257  rospy.logdebug("The action server has received a new goal request")
258 
259  # we need to check if this goal already lives in the status list
260  for st in self.status_list[:]:
261  if goal.goal_id.id == st.status.goal_id.id:
262  rospy.logdebug("Goal %s was already in the status list with status %i" % (goal.goal_id.id, st.status.status))
263  # Goal could already be in recalling state if a cancel came in before the goal
264  if st.status.status == GoalStatus.RECALLING:
265  st.status.status = GoalStatus.RECALLED
266  self.publish_result(st.status, self.ActionResultType())
267 
268  # if this is a request for a goal that has no active handles left,
269  # we'll bump how long it stays in the list
270  if st.handle_tracker is None:
271  st.handle_destruction_time = rospy.Time.now()
272 
273  # make sure not to call any user callbacks or add duplicate status onto the list
274  return
275 
276  # if the goal is not in our list, we need to create a StatusTracker associated with this goal and push it on
277  st = StatusTracker(None, None, goal)
278  self.status_list.append(st)
279 
280  # we need to create a handle tracker for the incoming goal and update the StatusTracker
281  handle_tracker = HandleTrackerDeleter(self, st)
282 
283  st.handle_tracker = handle_tracker
284 
285  # check if this goal has already been canceled based on its timestamp
286  gh = ServerGoalHandle(st, self, handle_tracker)
287  if goal.goal_id.stamp != rospy.Time() and goal.goal_id.stamp <= self.last_cancel:
288  # if it has... just create a GoalHandle for it and setCanceled
289  gh.set_canceled(None, "This goal handle was canceled by the action server because its timestamp is before the timestamp of the last cancel request")
290  else:
291  # now, we need to create a goal handle and call the user's callback
292  self.goal_callback(gh)
293 
294 
295  def publish_status_async(self, event):
296  with self.lock:
297  # we won't publish status unless we've been started
298  if not self.started:
299  return
300  self.publish_status()
301 
302 
303  def publish_status(self):
304  with self.lock:
305  # build a status array
306  status_array = GoalStatusArray()
307 
308  # status_array.set_status_list_size(len(self.status_list));
309 
310  i = 0
311  while i < len(self.status_list):
312  st = self.status_list[i]
313  # check if the item is due for deletion from the status list
314  if st.handle_destruction_time != rospy.Time() and st.handle_destruction_time + self.status_list_timeout < rospy.Time.now():
315  rospy.logdebug("Item %s with destruction time of %.3f being removed from list. Now = %.3f" %
316  (st.status.goal_id, st.handle_destruction_time.to_sec(), rospy.Time.now().to_sec()))
317  del self.status_list[i]
318  else:
319  status_array.status_list.append(st.status)
320  i += 1
321 
322  status_array.header.stamp = rospy.Time.now()
323  if not rospy.is_shutdown():
324  self.status_pub.publish(status_array)
actionlib.action_server.ActionServer.cancel_callback
cancel_callback
Definition: action_server.py:97
actionlib.action_server.ActionServer.ns
ns
Definition: action_server.py:64
actionlib.action_server.ActionServer.publish_feedback
def publish_feedback(self, status, feedback)
Publishes feedback for a given goal.
Definition: action_server.py:187
actionlib.action_server.ActionServer.internal_goal_callback
def internal_goal_callback(self, goal)
The ROS callback for goals coming into the ActionServer.
Definition: action_server.py:251
actionlib.action_server.ActionServer.publish_result
def publish_result(self, status, result)
Publishes a result for a given goal.
Definition: action_server.py:174
actionlib.action_server.ActionServer.goal_callback
goal_callback
Definition: action_server.py:94
actionlib.action_server.ActionServer.sub_queue_size
sub_queue_size
Definition: action_server.py:144
actionlib.action_server.ActionServer.status_timer
status_timer
Definition: action_server.py:85
actionlib.server_goal_handle
Definition: server_goal_handle.py:1
actionlib.action_server.ActionServer.ActionFeedback
ActionFeedback
Definition: action_server.py:73
actionlib.action_server.ActionServer.initialize
def initialize(self)
Initialize all ROS connections and setup timers.
Definition: action_server.py:136
actionlib.action_server.ActionServer.ActionResultType
ActionResultType
Definition: action_server.py:72
actionlib.handle_tracker_deleter.HandleTrackerDeleter
Definition: handle_tracker_deleter.py:33
actionlib.action_server.ActionServer.status_list_timeout
status_list_timeout
Definition: action_server.py:90
actionlib.exceptions
Definition: exceptions.py:1
actionlib.action_server.ActionServer.id_generator
id_generator
Definition: action_server.py:92
actionlib.action_server.ActionServer.status_frequency
status_frequency
Definition: action_server.py:155
actionlib.action_server.ActionServer.auto_start
auto_start
Definition: action_server.py:98
actionlib.goal_id_generator.GoalIDGenerator
Definition: goal_id_generator.py:41
actionlib.action_server.ActionServer.register_cancel_callback
def register_cancel_callback(self, cancel_cb)
Register a callback to be invoked when a new cancel is received, this will replace any previously reg...
Definition: action_server.py:114
actionlib.action_server.ActionServer.result_pub
result_pub
Definition: action_server.py:80
actionlib.server_goal_handle.ServerGoalHandle
Definition: server_goal_handle.py:35
actionlib.goal_id_generator
Definition: goal_id_generator.py:1
actionlib.action_server.ActionServer.pub_queue_size
pub_queue_size
Definition: action_server.py:137
actionlib.action_server.ActionServer.ActionGoal
ActionGoal
Definition: action_server.py:70
actionlib.action_server.ActionServer.register_goal_callback
def register_goal_callback(self, cb)
Register a callback to be invoked when a new goal is received, this will replace any previously regis...
Definition: action_server.py:109
actionlib.action_server.ActionServer.cancel_sub
cancel_sub
Definition: action_server.py:78
actionlib.status_tracker.StatusTracker
Definition: status_tracker.py:36
actionlib.action_server.ActionServer.status_list
status_list
Definition: action_server.py:87
actionlib.handle_tracker_deleter
Definition: handle_tracker_deleter.py:1
actionlib.action_server.nop_cb
def nop_cb(goal_handle)
Definition: action_server.py:44
actionlib.status_tracker
Definition: status_tracker.py:1
actionlib.exceptions.ActionException
Definition: exceptions.py:31
actionlib.action_server.ActionServer.start
def start(self)
Start the action server.
Definition: action_server.py:118
actionlib.action_server.ActionServer.last_cancel
last_cancel
Definition: action_server.py:89
actionlib.action_server.ActionServer
The ActionServer is a helpful tool for managing goal requests to a node. It allows the user to specif...
Definition: action_server.py:56
actionlib.action_server.ActionServer.status_pub
status_pub
Definition: action_server.py:79
actionlib.action_server.ActionServer.ActionResult
ActionResult
Definition: action_server.py:71
actionlib.action_server.ActionServer.internal_cancel_callback
def internal_cancel_callback(self, goal_id)
The ROS callback for cancel requests coming into the ActionServer.
Definition: action_server.py:197
actionlib.action_server.ActionServer.publish_status_async
def publish_status_async(self, event)
Publish status for all goals on a timer event.
Definition: action_server.py:295
actionlib.action_server.ActionServer.feedback_pub
feedback_pub
Definition: action_server.py:81
actionlib.action_server.ActionServer.lock
lock
Definition: action_server.py:83
actionlib.action_server.ActionServer.ActionSpec
ActionSpec
Definition: action_server.py:69
actionlib.action_server.ActionServer.__init__
def __init__(self, ns, ActionSpec, goal_cb, cancel_cb=nop_cb, auto_start=True)
Constructor for an ActionServer.
Definition: action_server.py:63
actionlib.action_server.ActionServer.publish_status
def publish_status(self)
Explicitly publish status.
Definition: action_server.py:303
actionlib.action_server.ActionServer.stop
def stop(self)
Stop the action server.
Definition: action_server.py:125
actionlib.action_server.ActionServer.started
started
Definition: action_server.py:100
actionlib.action_server.ActionServer.goal_sub
goal_sub
Definition: action_server.py:77


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