simple_action_client.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: Stuart Glaser
29 import rospy
30 import threading
31 
32 from actionlib_msgs.msg import GoalStatus
33 from actionlib.action_client import ActionClient, CommState, get_name_of_constant
34 
35 
37  PENDING = 0
38  ACTIVE = 1
39  DONE = 2
40 
41 
42 SimpleGoalState.to_string = classmethod(get_name_of_constant)
43 
44 
46 
53  def __init__(self, ns, ActionSpec):
54  self.action_client = ActionClient(ns, ActionSpec)
55  self.simple_state = SimpleGoalState.DONE
56  self.gh = None
57  self.done_condition = threading.Condition()
58 
59 
65  def wait_for_server(self, timeout=rospy.Duration()):
66  return self.action_client.wait_for_server(timeout)
67 
68 
82  def send_goal(self, goal, done_cb=None, active_cb=None, feedback_cb=None):
83  # destroys the old goal handle
84  self.stop_tracking_goal()
85 
86  self.done_cb = done_cb
87  self.active_cb = active_cb
88  self.feedback_cb = feedback_cb
89 
90  self.simple_state = SimpleGoalState.PENDING
91  self.gh = self.action_client.send_goal(goal, self._handle_transition, self._handle_feedback)
92 
93 
108  def send_goal_and_wait(self, goal, execute_timeout=rospy.Duration(), preempt_timeout=rospy.Duration()):
109  self.send_goal(goal)
110  if not self.wait_for_result(execute_timeout):
111  # preempt action
112  rospy.logdebug("Canceling goal")
113  self.cancel_goal()
114  if self.wait_for_result(preempt_timeout):
115  rospy.logdebug("Preempt finished within specified preempt_timeout [%.2f]", preempt_timeout.to_sec())
116  else:
117  rospy.logdebug("Preempt didn't finish specified preempt_timeout [%.2f]", preempt_timeout.to_sec())
118  return self.get_state()
119 
120 
123  def wait_for_result(self, timeout=rospy.Duration()):
124  if not self.gh:
125  rospy.logerr("Called wait_for_result when no goal exists")
126  return False
127 
128  timeout_time = rospy.get_rostime() + timeout
129  loop_period = rospy.Duration(0.1)
130  with self.done_condition:
131  while not rospy.is_shutdown():
132  time_left = timeout_time - rospy.get_rostime()
133  if timeout > rospy.Duration(0.0) and time_left <= rospy.Duration(0.0):
134  break
135 
136  if self.simple_state == SimpleGoalState.DONE:
137  break
138 
139  if time_left > loop_period or timeout == rospy.Duration():
140  time_left = loop_period
141 
142  self.done_condition.wait(time_left.to_sec())
143 
144  return self.simple_state == SimpleGoalState.DONE
145 
146 
147  def get_result(self):
148  if not self.gh:
149  rospy.logerr("Called get_result when no goal is running")
150  return None
151 
152  return self.gh.get_result()
153 
154 
161  def get_state(self):
162  if not self.gh:
163  return GoalStatus.LOST
164  status = self.gh.get_goal_status()
165 
166  if status == GoalStatus.RECALLING:
167  status = GoalStatus.PENDING
168  elif status == GoalStatus.PREEMPTING:
169  status = GoalStatus.ACTIVE
170 
171  return status
172 
173 
180  if not self.gh:
181  rospy.logerr("Called get_goal_status_text when no goal is running")
182  return "ERROR: Called get_goal_status_text when no goal is running"
183 
184  return self.gh.get_goal_status_text()
185 
186 
190  def cancel_all_goals(self):
192 
193 
200 
201 
202  def cancel_goal(self):
203  if self.gh:
204  self.gh.cancel()
205 
206 
211  self.gh = None
212 
213  def _handle_transition(self, gh):
214 
215  if gh != self.gh:
216  rospy.logerr("Got a transition callback on a goal handle that we're not tracking")
217  return
218 
219  comm_state = gh.get_comm_state()
220 
221  error_msg = "Received comm state %s when in simple state %s with SimpleActionClient in NS %s" % \
222  (CommState.to_string(comm_state), SimpleGoalState.to_string(self.simple_state), rospy.resolve_name(self.action_client.ns))
223 
224  if comm_state == CommState.ACTIVE:
225  if self.simple_state == SimpleGoalState.PENDING:
226  self._set_simple_state(SimpleGoalState.ACTIVE)
227  if self.active_cb:
228  self.active_cb()
229  elif self.simple_state == SimpleGoalState.DONE:
230  rospy.logerr(error_msg)
231  elif comm_state == CommState.RECALLING:
232  if self.simple_state != SimpleGoalState.PENDING:
233  rospy.logerr(error_msg)
234  elif comm_state == CommState.PREEMPTING:
235  if self.simple_state == SimpleGoalState.PENDING:
236  self._set_simple_state(SimpleGoalState.ACTIVE)
237  if self.active_cb:
238  self.active_cb()
239  elif self.simple_state == SimpleGoalState.DONE:
240  rospy.logerr(error_msg)
241  elif comm_state == CommState.DONE:
242  if self.simple_state in [SimpleGoalState.PENDING, SimpleGoalState.ACTIVE]:
243  if self.done_cb:
244  self.done_cb(gh.get_goal_status(), gh.get_result())
245  with self.done_condition:
246  self._set_simple_state(SimpleGoalState.DONE)
247  self.done_condition.notifyAll()
248  elif self.simple_state == SimpleGoalState.DONE:
249  rospy.logerr("SimpleActionClient received DONE twice")
250 
251  def _handle_feedback(self, gh, feedback):
252  if not self.gh:
253  # this is not actually an error - there can be a small window in which old feedback
254  # can be received between the time this variable is reset and a new goal is
255  # sent and confirmed
256  return
257  if gh != self.gh:
258  rospy.logerr("Got a feedback callback on a goal handle that we're not tracking. %s vs %s" %
259  (self.gh.comm_state_machine.action_goal.goal_id.id, gh.comm_state_machine.action_goal.goal_id.id))
260  return
261  if self.feedback_cb:
262  self.feedback_cb(feedback)
263 
264  def _set_simple_state(self, state):
265  self.simple_state = state
actionlib.simple_action_client.SimpleActionClient.send_goal
def send_goal(self, goal, done_cb=None, active_cb=None, feedback_cb=None)
Sends a goal to the ActionServer, and also registers callbacks.
Definition: simple_action_client.py:82
actionlib.simple_action_client.SimpleActionClient.wait_for_result
def wait_for_result(self, timeout=rospy.Duration())
Blocks until this goal transitions to done.
Definition: simple_action_client.py:123
actionlib.simple_action_client.SimpleActionClient.action_client
action_client
Definition: simple_action_client.py:54
actionlib.simple_action_client.SimpleActionClient
Definition: simple_action_client.py:45
actionlib.simple_action_client.SimpleActionClient._set_simple_state
def _set_simple_state(self, state)
Definition: simple_action_client.py:264
actionlib.simple_action_client.SimpleActionClient.cancel_all_goals
def cancel_all_goals(self)
Cancels all goals currently running on the action server.
Definition: simple_action_client.py:190
actionlib.simple_action_client.SimpleActionClient.get_result
def get_result(self)
Gets the Result of the current goal.
Definition: simple_action_client.py:147
actionlib.action_client
Definition: action_client.py:1
actionlib.simple_action_client.SimpleActionClient.gh
gh
Definition: simple_action_client.py:56
actionlib.simple_action_client.SimpleActionClient.done_condition
done_condition
Definition: simple_action_client.py:57
actionlib.simple_action_client.SimpleActionClient._handle_transition
def _handle_transition(self, gh)
Definition: simple_action_client.py:213
actionlib.simple_action_client.SimpleActionClient.get_state
def get_state(self)
Get the state information for this goal.
Definition: simple_action_client.py:161
actionlib.simple_action_client.SimpleActionClient.get_goal_status_text
def get_goal_status_text(self)
Returns the current status text of the goal.
Definition: simple_action_client.py:179
actionlib.simple_action_client.SimpleActionClient.feedback_cb
feedback_cb
Definition: simple_action_client.py:88
actionlib.simple_action_client.SimpleActionClient.cancel_goals_at_and_before_time
def cancel_goals_at_and_before_time(self, time)
Cancels all goals prior to a given timestamp.
Definition: simple_action_client.py:198
actionlib.simple_action_client.SimpleActionClient.active_cb
active_cb
Definition: simple_action_client.py:87
actionlib.simple_action_client.SimpleActionClient._handle_feedback
def _handle_feedback(self, gh, feedback)
Definition: simple_action_client.py:251
actionlib.simple_action_client.SimpleActionClient.done_cb
done_cb
Definition: simple_action_client.py:86
actionlib.simple_action_client.SimpleActionClient.stop_tracking_goal
def stop_tracking_goal(self)
Stops tracking the state of the current goal.
Definition: simple_action_client.py:210
actionlib.simple_action_client.SimpleActionClient.simple_state
simple_state
Definition: simple_action_client.py:55
actionlib.simple_action_client.SimpleActionClient.__init__
def __init__(self, ns, ActionSpec)
Constructs a SimpleActionClient and opens connections to an ActionServer.
Definition: simple_action_client.py:53
actionlib.simple_action_client.SimpleActionClient.cancel_goal
def cancel_goal(self)
Cancels the goal that we are currently pursuing.
Definition: simple_action_client.py:202
actionlib.action_client.ActionClient
Definition: action_client.py:498
actionlib.simple_action_client.SimpleGoalState
Definition: simple_action_client.py:36
actionlib.simple_action_client.SimpleActionClient.send_goal_and_wait
def send_goal_and_wait(self, goal, execute_timeout=rospy.Duration(), preempt_timeout=rospy.Duration())
Sends a goal to the ActionServer, waits for the goal to complete, and preempts goal is necessary.
Definition: simple_action_client.py:108
actionlib.simple_action_client.SimpleActionClient.wait_for_server
def wait_for_server(self, timeout=rospy.Duration())
Blocks until the action server connects to this client.
Definition: simple_action_client.py:65


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