action_client.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: Stuart Glaser
30 '''
31 Example:
32 
33 from move_base.msg import *
34 rospy.init_node('foo')
35 
36 
37 from move_base.msg import *
38 from geometry_msgs.msg import *
39 g1 = MoveBaseGoal(PoseStamped(Header(frame_id = 'base_link'),
40  Pose(Point(2, 0, 0),
41  Quaternion(0, 0, 0, 1))))
42 g2 = MoveBaseGoal(PoseStamped(Header(frame_id = 'base_link'),
43  Pose(Point(5, 0, 0),
44  Quaternion(0, 0, 0, 1))))
45 
46 client = ActionClient('move_base', MoveBaseAction)
47 
48 h1 = client.send_goal(g1)
49 h2 = client.send_goal(g2)
50 client.cancel_all_goals()
51 '''
52 
53 import threading
54 import weakref
55 import time
56 import rospy
57 from rospy import Header
58 from actionlib_msgs.msg import GoalID, GoalStatus, GoalStatusArray
59 from actionlib.exceptions import ActionException
60 
61 g_goal_id = 1
62 
63 
65  for k, v in C.__dict__.items():
66  if isinstance(v, int) and v == n:
67  return k
68  return "NO_SUCH_STATE_%d" % n
69 
70 
71 class CommState(object):
72  WAITING_FOR_GOAL_ACK = 0
73  PENDING = 1
74  ACTIVE = 2
75  WAITING_FOR_RESULT = 3
76  WAITING_FOR_CANCEL_ACK = 4
77  RECALLING = 5
78  PREEMPTING = 6
79  DONE = 7
80  LOST = 8
81 
82 
83 class TerminalState(object):
84  RECALLED = GoalStatus.RECALLED
85  REJECTED = GoalStatus.REJECTED
86  PREEMPTED = GoalStatus.PREEMPTED
87  ABORTED = GoalStatus.ABORTED
88  SUCCEEDED = GoalStatus.SUCCEEDED
89  LOST = GoalStatus.LOST
90 
91 
92 GoalStatus.to_string = classmethod(get_name_of_constant)
93 CommState.to_string = classmethod(get_name_of_constant)
94 TerminalState.to_string = classmethod(get_name_of_constant)
95 
96 
97 def _find_status_by_goal_id(status_array, id):
98  for s in status_array.status_list:
99  if s.goal_id.id == id:
100  return s
101  return None
102 
103 
104 ## @brief Client side handle to monitor goal progress.
105 
111  ## @brief Internal use only
112 
115  def __init__(self, comm_state_machine):
116  self.comm_state_machine = comm_state_machine
117 
118  # print "GH created. id = %.3f" % self.comm_state_machine.action_goal.goal_id.stamp.to_sec()
119 
120  ## @brief True iff the two ClientGoalHandle's are tracking the same goal
121  def __eq__(self, o):
122  if not o:
123  return False
124  return self.comm_state_machine == o.comm_state_machine
125 
126  ## @brief True iff the two ClientGoalHandle's are tracking different goals
127  def __ne__(self, o):
128  if not o:
129  return True
130  return not (self.comm_state_machine == o.comm_state_machine)
131 
132  ## @brieft Hash function for ClientGoalHandle
133  def __hash__(self):
134  return hash(self.comm_state_machine)
135 
136  ## @brief Sends a cancel message for this specific goal to the ActionServer.
137 
139  def cancel(self):
140  with self.comm_state_machine.mutex:
141  cancel_msg = GoalID(stamp=rospy.Time(0),
142  id=self.comm_state_machine.action_goal.goal_id.id)
143  self.comm_state_machine.send_cancel_fn(cancel_msg)
144  self.comm_state_machine.transition_to(CommState.WAITING_FOR_CANCEL_ACK)
145 
146  ## @brief Get the state of this goal's communication state machine from interaction with the server
147 
152  def get_comm_state(self):
153  if not self.comm_state_machine:
154  rospy.logerr("Trying to get_comm_state on an inactive ClientGoalHandle.")
155  return CommState.LOST
156  return self.comm_state_machine.state
157 
158  ## @brief Returns the current status of the goal.
159 
164  def get_goal_status(self):
165  if not self.comm_state_machine:
166  rospy.logerr("Trying to get_goal_status on an inactive ClientGoalHandle.")
167  return GoalStatus.PENDING
168  return self.comm_state_machine.latest_goal_status.status
169 
170  ## @brief Returns the current status text of the goal.
171 
176  if not self.comm_state_machine:
177  rospy.logerr("Trying to get_goal_status_text on an inactive ClientGoalHandle.")
178  return "ERROR: Trying to get_goal_status_text on an inactive ClientGoalHandle."
179  return self.comm_state_machine.latest_goal_status.text
180 
181  ## @brief Gets the result produced by the action server for this goal.
182 
184  def get_result(self):
185  if not self.comm_state_machine:
186  rospy.logerr("Trying to get_result on an inactive ClientGoalHandle.")
187  return None
188  if not self.comm_state_machine.latest_result:
189  # rospy.logerr("Trying to get_result on a ClientGoalHandle when no result has been received.")
190  return None
191  return self.comm_state_machine.latest_result.result
192 
193  ## @brief Gets the terminal state information for this goal.
194 
200  if not self.comm_state_machine:
201  rospy.logerr("Trying to get_terminal_state on an inactive ClientGoalHandle.")
202  return GoalStatus.LOST
203 
204  with self.comm_state_machine.mutex:
205  if self.comm_state_machine.state != CommState.DONE:
206  rospy.logwarn("Asking for the terminal state when we're in [%s]",
207  CommState.to_string(self.comm_state_machine.state))
208 
209  goal_status = self.comm_state_machine.latest_goal_status.status
210  if goal_status in [GoalStatus.PREEMPTED, GoalStatus.SUCCEEDED,
211  GoalStatus.ABORTED, GoalStatus.REJECTED,
212  GoalStatus.RECALLED, GoalStatus.LOST]:
213  return goal_status
214 
215  rospy.logerr("Asking for a terminal state, but the goal status is %d", goal_status)
216  return GoalStatus.LOST
217 
218 
219 NO_TRANSITION = -1
220 INVALID_TRANSITION = -2
221 _transitions = {
222  CommState.WAITING_FOR_GOAL_ACK: {
223  GoalStatus.PENDING: CommState.PENDING,
224  GoalStatus.ACTIVE: CommState.ACTIVE,
225  GoalStatus.REJECTED: (CommState.PENDING, CommState.WAITING_FOR_RESULT),
226  GoalStatus.RECALLING: (CommState.PENDING, CommState.RECALLING),
227  GoalStatus.RECALLED: (CommState.PENDING, CommState.WAITING_FOR_RESULT),
228  GoalStatus.PREEMPTED: (CommState.ACTIVE, CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
229  GoalStatus.SUCCEEDED: (CommState.ACTIVE, CommState.WAITING_FOR_RESULT),
230  GoalStatus.ABORTED: (CommState.ACTIVE, CommState.WAITING_FOR_RESULT),
231  GoalStatus.PREEMPTING: (CommState.ACTIVE, CommState.PREEMPTING)},
232  CommState.PENDING: {
233  GoalStatus.PENDING: NO_TRANSITION,
234  GoalStatus.ACTIVE: CommState.ACTIVE,
235  GoalStatus.REJECTED: CommState.WAITING_FOR_RESULT,
236  GoalStatus.RECALLING: CommState.RECALLING,
237  GoalStatus.RECALLED: (CommState.RECALLING, CommState.WAITING_FOR_RESULT),
238  GoalStatus.PREEMPTED: (CommState.ACTIVE, CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
239  GoalStatus.SUCCEEDED: (CommState.ACTIVE, CommState.WAITING_FOR_RESULT),
240  GoalStatus.ABORTED: (CommState.ACTIVE, CommState.WAITING_FOR_RESULT),
241  GoalStatus.PREEMPTING: (CommState.ACTIVE, CommState.PREEMPTING)},
242  CommState.ACTIVE: {
243  GoalStatus.PENDING: INVALID_TRANSITION,
244  GoalStatus.ACTIVE: NO_TRANSITION,
245  GoalStatus.REJECTED: INVALID_TRANSITION,
246  GoalStatus.RECALLING: INVALID_TRANSITION,
247  GoalStatus.RECALLED: INVALID_TRANSITION,
248  GoalStatus.PREEMPTED: (CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
249  GoalStatus.SUCCEEDED: CommState.WAITING_FOR_RESULT,
250  GoalStatus.ABORTED: CommState.WAITING_FOR_RESULT,
251  GoalStatus.PREEMPTING: CommState.PREEMPTING},
252  CommState.WAITING_FOR_RESULT: {
253  GoalStatus.PENDING: INVALID_TRANSITION,
254  GoalStatus.ACTIVE: NO_TRANSITION,
255  GoalStatus.REJECTED: NO_TRANSITION,
256  GoalStatus.RECALLING: INVALID_TRANSITION,
257  GoalStatus.RECALLED: NO_TRANSITION,
258  GoalStatus.PREEMPTED: NO_TRANSITION,
259  GoalStatus.SUCCEEDED: NO_TRANSITION,
260  GoalStatus.ABORTED: NO_TRANSITION,
261  GoalStatus.PREEMPTING: INVALID_TRANSITION},
262  CommState.WAITING_FOR_CANCEL_ACK: {
263  GoalStatus.PENDING: NO_TRANSITION,
264  GoalStatus.ACTIVE: NO_TRANSITION,
265  GoalStatus.REJECTED: CommState.WAITING_FOR_RESULT,
266  GoalStatus.RECALLING: CommState.RECALLING,
267  GoalStatus.RECALLED: (CommState.RECALLING, CommState.WAITING_FOR_RESULT),
268  GoalStatus.PREEMPTED: (CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
269  GoalStatus.SUCCEEDED: (CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
270  GoalStatus.ABORTED: (CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
271  GoalStatus.PREEMPTING: CommState.PREEMPTING},
272  CommState.RECALLING: {
273  GoalStatus.PENDING: INVALID_TRANSITION,
274  GoalStatus.ACTIVE: INVALID_TRANSITION,
275  GoalStatus.REJECTED: CommState.WAITING_FOR_RESULT,
276  GoalStatus.RECALLING: NO_TRANSITION,
277  GoalStatus.RECALLED: CommState.WAITING_FOR_RESULT,
278  GoalStatus.PREEMPTED: (CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
279  GoalStatus.SUCCEEDED: (CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
280  GoalStatus.ABORTED: (CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
281  GoalStatus.PREEMPTING: CommState.PREEMPTING},
282  CommState.PREEMPTING: {
283  GoalStatus.PENDING: INVALID_TRANSITION,
284  GoalStatus.ACTIVE: INVALID_TRANSITION,
285  GoalStatus.REJECTED: INVALID_TRANSITION,
286  GoalStatus.RECALLING: INVALID_TRANSITION,
287  GoalStatus.RECALLED: INVALID_TRANSITION,
288  GoalStatus.PREEMPTED: CommState.WAITING_FOR_RESULT,
289  GoalStatus.SUCCEEDED: CommState.WAITING_FOR_RESULT,
290  GoalStatus.ABORTED: CommState.WAITING_FOR_RESULT,
291  GoalStatus.PREEMPTING: NO_TRANSITION},
292  CommState.DONE: {
293  GoalStatus.PENDING: INVALID_TRANSITION,
294  GoalStatus.ACTIVE: INVALID_TRANSITION,
295  GoalStatus.REJECTED: NO_TRANSITION,
296  GoalStatus.RECALLING: INVALID_TRANSITION,
297  GoalStatus.RECALLED: NO_TRANSITION,
298  GoalStatus.PREEMPTED: NO_TRANSITION,
299  GoalStatus.SUCCEEDED: NO_TRANSITION,
300  GoalStatus.ABORTED: NO_TRANSITION,
301  GoalStatus.PREEMPTING: INVALID_TRANSITION}}
302 
303 
305  def __init__(self, action_goal, transition_cb, feedback_cb, send_goal_fn, send_cancel_fn):
306  self.action_goal = action_goal
307  self.transition_cb = transition_cb
308  self.feedback_cb = feedback_cb
309  self.send_goal_fn = send_goal_fn
310  self.send_cancel_fn = send_cancel_fn
311 
312  self.state = CommState.WAITING_FOR_GOAL_ACK
313  self.mutex = threading.RLock()
314  self.latest_goal_status = GoalStatus(status=GoalStatus.PENDING)
315  self.latest_result = None
316 
317  def __eq__(self, o):
318  return self.action_goal.goal_id.id == o.action_goal.goal_id.id
319 
320  ## @brieft Hash function for CommStateMachine
321  def __hash__(self):
322  return hash(self.action_goal.goal_id.id)
323 
324  def set_state(self, state):
325  rospy.logdebug("Transitioning CommState from %s to %s",
326  CommState.to_string(self.state), CommState.to_string(state))
327  self.state = state
328 
329 
332  def update_status(self, status_array):
333  with self.mutex:
334  if self.state == CommState.DONE:
335  return
336 
337  status = _find_status_by_goal_id(status_array, self.action_goal.goal_id.id)
338 
339  # You mean you haven't heard of me?
340  if not status:
341  if self.state not in [CommState.WAITING_FOR_GOAL_ACK,
342  CommState.WAITING_FOR_RESULT,
343  CommState.DONE]:
344  self._mark_as_lost()
345  return
346 
347  self.latest_goal_status = status
348 
349  # Determines the next state from the lookup table
350  if self.state not in _transitions:
351  rospy.logerr("CommStateMachine is in a funny state: %i" % self.state)
352  return
353  if status.status not in _transitions[self.state]:
354  rospy.logerr("Got an unknown status from the ActionServer: %i" % status.status)
355  return
356  next_state = _transitions[self.state][status.status]
357 
358  # Knowing the next state, what should we do?
359  if next_state == NO_TRANSITION:
360  pass
361  elif next_state == INVALID_TRANSITION:
362  rospy.logerr("Invalid goal status transition from %s to %s" %
363  (CommState.to_string(self.state), GoalStatus.to_string(status.status)))
364  else:
365  if hasattr(next_state, '__getitem__'):
366  for s in next_state:
367  self.transition_to(s)
368  else:
369  self.transition_to(next_state)
370 
371  def transition_to(self, state):
372  rospy.logdebug("Transitioning to %s (from %s, goal: %s)",
373  CommState.to_string(state), CommState.to_string(self.state),
374  self.action_goal.goal_id.id)
375  self.state = state
376  if self.transition_cb:
377  self.transition_cb(ClientGoalHandle(self))
378 
379  def _mark_as_lost(self):
380  self.latest_goal_status.status = GoalStatus.LOST
381  self.transition_to(CommState.DONE)
382 
383  def update_result(self, action_result):
384  # Might not be for us
385  if self.action_goal.goal_id.id != action_result.status.goal_id.id:
386  return
387 
388  with self.mutex:
389  self.latest_goal_status = action_result.status
390  self.latest_result = action_result
391 
392  if self.state in [CommState.WAITING_FOR_GOAL_ACK,
393  CommState.WAITING_FOR_CANCEL_ACK,
394  CommState.PENDING,
395  CommState.ACTIVE,
396  CommState.WAITING_FOR_RESULT,
397  CommState.RECALLING,
398  CommState.PREEMPTING]:
399  # Stuffs the goal status in the result into a GoalStatusArray
400  status_array = GoalStatusArray()
401  status_array.status_list.append(action_result.status)
402  self.update_status(status_array)
403 
404  self.transition_to(CommState.DONE)
405  elif self.state == CommState.DONE:
406  rospy.logerr("Got a result when we were already in the DONE state")
407  else:
408  rospy.logerr("In a funny state: %i" % self.state)
409 
410  def update_feedback(self, action_feedback):
411  # Might not be for us
412  if self.action_goal.goal_id.id != action_feedback.status.goal_id.id:
413  return
414 
415  # with self.mutex:
416  if self.feedback_cb and self.state != CommState.DONE:
417  self.feedback_cb(ClientGoalHandle(self), action_feedback.feedback)
418 
419 
421 
422  # statuses - a list of weak references to CommStateMachine objects
423 
424  def __init__(self, ActionSpec):
425  self.list_mutex = threading.RLock()
426  self.statuses = []
427  self.send_goal_fn = None
428 
429  try:
430  a = ActionSpec()
431 
432  self.ActionSpec = ActionSpec
433  self.ActionGoal = type(a.action_goal)
434  self.ActionResult = type(a.action_result)
435  self.ActionFeedback = type(a.action_feedback)
436  except AttributeError:
437  raise ActionException("Type is not an action spec: %s" % str(ActionSpec))
438 
439  def _generate_id(self):
440  global g_goal_id
441  id, g_goal_id = g_goal_id, g_goal_id + 1
442  now = rospy.Time.now()
443  return GoalID(id="%s-%i-%.3f" % (rospy.get_caller_id(), id, now.to_sec()), stamp=now)
444 
445  def register_send_goal_fn(self, fn):
446  self.send_goal_fn = fn
447 
448  def register_cancel_fn(self, fn):
449  self.cancel_fn = fn
450 
451  ## Sends off a goal and starts tracking its status.
452 
454  def init_goal(self, goal, transition_cb=None, feedback_cb=None):
455  action_goal = self.ActionGoal(header=Header(),
456  goal_id=self._generate_id(),
457  goal=goal)
458  action_goal.header.stamp = rospy.get_rostime()
459 
460  csm = CommStateMachine(action_goal, transition_cb, feedback_cb,
461  self.send_goal_fn, self.cancel_fn)
462 
463  with self.list_mutex:
464  self.statuses.append(weakref.ref(csm))
465 
466  self.send_goal_fn(action_goal)
467 
468  return ClientGoalHandle(csm)
469 
470  # Pulls out the statuses that are still live (creating strong
471  # references to them)
473  with self.list_mutex:
474  live_statuses = [r() for r in self.statuses]
475  live_statuses = filter(lambda x: x, live_statuses)
476  return live_statuses
477 
478  ## Updates the statuses of all goals from the information in status_array.
479 
481  def update_statuses(self, status_array):
482 
483  with self.list_mutex:
484  # Garbage collects dead status objects
485  self.statuses = [r for r in self.statuses if r()]
486 
487  for status in self._get_live_statuses():
488  status.update_status(status_array)
489 
490  def update_results(self, action_result):
491  for status in self._get_live_statuses():
492  status.update_result(action_result)
493 
494  def update_feedbacks(self, action_feedback):
495  for status in self._get_live_statuses():
496  status.update_feedback(action_feedback)
497 
498 
500  ## @brief Constructs an ActionClient and opens connections to an ActionServer.
501 
507  def __init__(self, ns, ActionSpec):
508  self.ns = ns
509  self.last_status_msg = None
510 
511  try:
512  a = ActionSpec()
513 
514  self.ActionSpec = ActionSpec
515  self.ActionGoal = type(a.action_goal)
516  self.ActionResult = type(a.action_result)
517  self.ActionFeedback = type(a.action_feedback)
518  except AttributeError:
519  raise ActionException("Type is not an action spec: %s" % str(ActionSpec))
520 
521  self.pub_queue_size = rospy.get_param('actionlib_client_pub_queue_size', 10)
522  if self.pub_queue_size < 0:
523  self.pub_queue_size = 10
524  self.pub_goal = rospy.Publisher(rospy.remap_name(ns) + '/goal', self.ActionGoal, queue_size=self.pub_queue_size)
525  self.pub_cancel = rospy.Publisher(rospy.remap_name(ns) + '/cancel', GoalID, queue_size=self.pub_queue_size)
526 
527  self.manager = GoalManager(ActionSpec)
528  self.manager.register_send_goal_fn(self.pub_goal.publish)
529  self.manager.register_cancel_fn(self.pub_cancel.publish)
530 
531  self.sub_queue_size = rospy.get_param('actionlib_client_sub_queue_size', -1)
532  if self.sub_queue_size < 0:
533  self.sub_queue_size = None
534  self.status_sub = rospy.Subscriber(rospy.remap_name(ns) + '/status', GoalStatusArray, callback=self._status_cb, queue_size=self.sub_queue_size)
535  self.result_sub = rospy.Subscriber(rospy.remap_name(ns) + '/result', self.ActionResult, callback=self._result_cb, queue_size=self.sub_queue_size)
536  self.feedback_sub = rospy.Subscriber(rospy.remap_name(ns) + '/feedback', self.ActionFeedback, callback=self._feedback_cb, queue_size=self.sub_queue_size)
537 
538  ## @brief Sends a goal to the action server
539 
552  def send_goal(self, goal, transition_cb=None, feedback_cb=None):
553  return self.manager.init_goal(goal, transition_cb, feedback_cb)
554 
555  ## @brief Cancels all goals currently running on the action server.
556 
559  def cancel_all_goals(self):
560  cancel_msg = GoalID(stamp=rospy.Time.from_sec(0.0), id="")
561  self.pub_cancel.publish(cancel_msg)
562 
563  ## @brief Cancels all goals prior to a given timestamp
564 
568 
570  cancel_msg = GoalID(stamp=time, id="")
571  self.pub_cancel.publish(cancel_msg)
572 
573  ## @brief [Deprecated] Use wait_for_server
574  def wait_for_action_server_to_start(self, timeout=rospy.Duration(0.0)):
575  return self.wait_for_server(timeout)
576 
577  ## @brief Waits for the ActionServer to connect to this client
578 
582  def wait_for_server(self, timeout=rospy.Duration(0.0)):
583  started = False
584  timeout_time = rospy.get_rostime() + timeout
585  while not rospy.is_shutdown():
586  if self.last_status_msg:
587  server_id = self.last_status_msg._connection_header['callerid']
588 
589  if self.pub_goal.impl.has_connection(server_id) and \
590  self.pub_cancel.impl.has_connection(server_id):
591  # We'll also check that all of the subscribers have at least
592  # one publisher, this isn't a perfect check, but without
593  # publisher callbacks... it'll have to do
594  status_num_pubs = 0
595  for stat in self.status_sub.impl.get_stats()[1]:
596  if stat[4]:
597  status_num_pubs += 1
598 
599  result_num_pubs = 0
600  for stat in self.result_sub.impl.get_stats()[1]:
601  if stat[4]:
602  result_num_pubs += 1
603 
604  feedback_num_pubs = 0
605  for stat in self.feedback_sub.impl.get_stats()[1]:
606  if stat[4]:
607  feedback_num_pubs += 1
608 
609  if status_num_pubs > 0 and result_num_pubs > 0 and feedback_num_pubs > 0:
610  started = True
611  break
612 
613  if timeout != rospy.Duration(0.0) and rospy.get_rostime() >= timeout_time:
614  break
615 
616  time.sleep(0.01)
617 
618  return started
619 
620  def _status_cb(self, msg):
621  self.last_status_msg = msg
622  self.manager.update_statuses(msg)
623 
624  def _result_cb(self, msg):
625  self.manager.update_results(msg)
626 
627  def _feedback_cb(self, msg):
628  self.manager.update_feedbacks(msg)
def __init__(self, action_goal, transition_cb, feedback_cb, send_goal_fn, send_cancel_fn)
def update_feedback(self, action_feedback)
Client side handle to monitor goal progress.
def cancel_all_goals(self)
Cancels all goals currently running on the action server.
def cancel(self)
Sends a cancel message for this specific goal to the ActionServer.
def send_goal(self, goal, transition_cb=None, feedback_cb=None)
Sends a goal to the action server.
def wait_for_server(self, timeout=rospy.Duration(0.0))
Waits for the ActionServer to connect to this client.
def _find_status_by_goal_id(status_array, id)
def wait_for_action_server_to_start(self, timeout=rospy.Duration(0.0))
[Deprecated] Use wait_for_server
def init_goal(self, goal, transition_cb=None, feedback_cb=None)
Sends off a goal and starts tracking its status.
def get_goal_status_text(self)
Returns the current status text of the goal.
def __eq__(self, o)
True iff the two ClientGoalHandle&#39;s are tracking the same goal.
def update_results(self, action_result)
def cancel_goals_at_and_before_time(self, time)
Cancels all goals prior to a given timestamp.
def get_name_of_constant(C, n)
def __init__(self, comm_state_machine)
Internal use only.
def update_feedbacks(self, action_feedback)
def get_goal_status(self)
Returns the current status of the goal.
def __ne__(self, o)
True iff the two ClientGoalHandle&#39;s are tracking different goals.
def get_terminal_state(self)
Gets the terminal state information for this goal.
def get_comm_state(self)
Get the state of this goal&#39;s communication state machine from interaction with the server...
def get_result(self)
Gets the result produced by the action server for this goal.
def __init__(self, ns, ActionSpec)
Constructs an ActionClient and opens connections to an ActionServer.
def update_result(self, action_result)
def __hash__(self)
Hash function for CommStateMachine
def __hash__(self)
Hash function for ClientGoalHandle
def update_statuses(self, status_array)
Updates the statuses of all goals from the information in status_array.


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Mon Aug 24 2020 03:40:47