$search
00001 #! /usr/bin/env python 00002 # Copyright (c) 2009, Willow Garage, Inc. 00003 # All rights reserved. 00004 # 00005 # Redistribution and use in source and binary forms, with or without 00006 # modification, are permitted provided that the following conditions are met: 00007 # 00008 # * Redistributions of source code must retain the above copyright 00009 # notice, this list of conditions and the following disclaimer. 00010 # * Redistributions in binary form must reproduce the above copyright 00011 # notice, this list of conditions and the following disclaimer in the 00012 # documentation and/or other materials provided with the distribution. 00013 # * Neither the name of the Willow Garage, Inc. nor the names of its 00014 # contributors may be used to endorse or promote products derived from 00015 # this software without specific prior written permission. 00016 # 00017 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 # POSSIBILITY OF SUCH DAMAGE. 00028 00029 # Author: Stuart Glaser 00030 00031 from __future__ import with_statement 00032 import roslib; roslib.load_manifest('actionlib') 00033 import threading 00034 import time 00035 import rospy 00036 from rospy import Header 00037 from actionlib_msgs.msg import * 00038 from action_client import ActionClient, CommState, get_name_of_constant 00039 00040 class SimpleGoalState: 00041 PENDING = 0 00042 ACTIVE = 1 00043 DONE = 2 00044 SimpleGoalState.to_string = classmethod(get_name_of_constant) 00045 00046 00047 class SimpleActionClient: 00048 ## @brief Constructs a SimpleActionClient and opens connections to an ActionServer. 00049 ## 00050 ## @param ns The namespace in which to access the action. For 00051 ## example, the "goal" topic should occur under ns/goal 00052 ## 00053 ## @param ActionSpec The *Action message type. The SimpleActionClient 00054 ## will grab the other message types from this type. 00055 def __init__(self, ns, ActionSpec): 00056 self.action_client = ActionClient(ns, ActionSpec) 00057 self.simple_state = SimpleGoalState.DONE 00058 self.gh = None 00059 self.done_condition = threading.Condition() 00060 00061 ## @brief Blocks until the action server connects to this client 00062 ## 00063 ## @param timeout Max time to block before returning. A zero 00064 ## timeout is interpreted as an infinite timeout. 00065 ## 00066 ## @return True if the server connected in the allocated time. False on timeout 00067 def wait_for_server(self, timeout = rospy.Duration()): 00068 return self.action_client.wait_for_server(timeout) 00069 00070 00071 ## @brief Sends a goal to the ActionServer, and also registers callbacks 00072 ## 00073 ## If a previous goal is already active when this is called. We simply forget 00074 ## about that goal and start tracking the new goal. No cancel requests are made. 00075 ## 00076 ## @param done_cb Callback that gets called on transitions to 00077 ## Done. The callback should take two parameters: the terminal 00078 ## state (as an integer from actionlib_msgs/GoalStatus) and the 00079 ## result. 00080 ## 00081 ## @param active_cb No-parameter callback that gets called on transitions to Active. 00082 ## 00083 ## @param feedback_cb Callback that gets called whenever feedback 00084 ## for this goal is received. Takes one parameter: the feedback. 00085 def send_goal(self, goal, done_cb = None, active_cb = None, feedback_cb = None): 00086 # destroys the old goal handle 00087 self.stop_tracking_goal() 00088 00089 self.done_cb = done_cb 00090 self.active_cb = active_cb 00091 self.feedback_cb = feedback_cb 00092 00093 self.simple_state = SimpleGoalState.PENDING 00094 self.gh = self.action_client.send_goal(goal, self._handle_transition, self._handle_feedback) 00095 00096 00097 ## @brief Sends a goal to the ActionServer, waits for the goal to complete, and preempts goal is necessary 00098 ## 00099 ## If a previous goal is already active when this is called. We simply forget 00100 ## about that goal and start tracking the new goal. No cancel requests are made. 00101 ## 00102 ## If the goal does not complete within the execute_timeout, the goal gets preempted 00103 ## 00104 ## If preemption of the goal does not complete withing the preempt_timeout, this 00105 ## method simply returns 00106 ## 00107 ## @param execute_timeout The time to wait for the goal to complete 00108 ## 00109 ## @param preempt_timeout The time to wait for preemption to complete 00110 ## 00111 ## @return The goal's state. 00112 def send_goal_and_wait(self, goal, execute_timeout = rospy.Duration(), preempt_timeout = rospy.Duration()): 00113 self.send_goal(goal) 00114 if not self.wait_for_result(execute_timeout): 00115 # preempt action 00116 rospy.logdebug("Canceling goal") 00117 self.cancel_goal() 00118 if self.wait_for_result(preempt_timeout): 00119 rospy.logdebug("Preempt finished within specified preempt_timeout [%.2f]", preempt_timeout.to_sec()); 00120 else: 00121 rospy.logdebug("Preempt didn't finish specified preempt_timeout [%.2f]", preempt_timeout.to_sec()); 00122 return self.get_state() 00123 00124 00125 ## @brief Blocks until this goal transitions to done 00126 ## @param timeout Max time to block before returning. A zero timeout is interpreted as an infinite timeout. 00127 ## @return True if the goal finished. False if the goal didn't finish within the allocated timeout 00128 def wait_for_result(self, timeout = rospy.Duration()): 00129 if not self.gh: 00130 rospy.logerr("Called wait_for_goal_to_finish when no goal exists") 00131 return False 00132 00133 timeout_time = rospy.get_rostime() + timeout 00134 loop_period = rospy.Duration(0.1) 00135 with self.done_condition: 00136 while not rospy.is_shutdown(): 00137 time_left = timeout_time - rospy.get_rostime() 00138 if timeout > rospy.Duration(0.0) and time_left <= rospy.Duration(0.0): 00139 break 00140 00141 if self.simple_state == SimpleGoalState.DONE: 00142 break 00143 00144 if time_left > loop_period or timeout == rospy.Duration(): 00145 time_left = loop_period 00146 00147 self.done_condition.wait(time_left.to_sec()) 00148 00149 return self.simple_state == SimpleGoalState.DONE 00150 00151 00152 ## @brief Gets the Result of the current goal 00153 def get_result(self): 00154 if not self.gh: 00155 rospy.logerr("Called get_result when no goal is running") 00156 return None 00157 00158 return self.gh.get_result() 00159 00160 00161 ## @brief Get the state information for this goal 00162 ## 00163 ## Possible States Are: PENDING, ACTIVE, RECALLED, REJECTED, 00164 ## PREEMPTED, ABORTED, SUCCEEDED, LOST. 00165 ## 00166 ## @return The goal's state. Returns LOST if this 00167 ## SimpleActionClient isn't tracking a goal. 00168 def get_state(self): 00169 if not self.gh: 00170 rospy.logerr("Called get_state when no goal is running") 00171 return GoalStatus.LOST 00172 status = self.gh.get_goal_status() 00173 00174 if status == GoalStatus.RECALLING: 00175 status = GoalStatus.PENDING 00176 elif status == GoalStatus.PREEMPTING: 00177 status = GoalStatus.ACTIVE 00178 00179 return status 00180 00181 00182 ## @brief Returns the current status text of the goal. 00183 ## 00184 ## The text is sent by the action server. It is designed to 00185 ## help debugging issues on the server side. 00186 ## 00187 ## @return The current status text of the goal. 00188 def get_goal_status_text(self): 00189 if not self.gh: 00190 rospy.logerr("Called get_goal_status_text when no goal is running") 00191 return "ERROR: Called get_goal_status_text when no goal is running" 00192 00193 return self.gh.get_goal_status_text() 00194 00195 00196 00197 00198 ## @brief Cancels all goals currently running on the action server 00199 ## 00200 ## This preempts all goals running on the action server at the point that 00201 ## this message is serviced by the ActionServer. 00202 def cancel_all_goals(self): 00203 self.action_client.cancel_all_goals() 00204 00205 00206 ## @brief Cancels all goals prior to a given timestamp 00207 ## 00208 ## This preempts all goals running on the action server for which the 00209 ## time stamp is earlier than the specified time stamp 00210 ## this message is serviced by the ActionServer. 00211 00212 def cancel_goals_at_and_before_time(self, time): 00213 self.action_client.cancel_goals_at_and_before_time(time) 00214 00215 00216 ## @brief Cancels the goal that we are currently pursuing 00217 def cancel_goal(self): 00218 if self.gh: 00219 self.gh.cancel() 00220 00221 00222 ## @brief Stops tracking the state of the current goal. Unregisters this goal's callbacks 00223 ## 00224 ## This is useful if we want to make sure we stop calling our callbacks before sending a new goal. 00225 ## Note that this does not cancel the goal, it simply stops looking for status info about this goal. 00226 def stop_tracking_goal(self): 00227 self.gh = None 00228 00229 def _handle_transition(self, gh): 00230 comm_state = gh.get_comm_state() 00231 00232 error_msg = "Received comm state %s when in simple state %s with SimpleActionClient in NS %s" % \ 00233 (CommState.to_string(comm_state), SimpleGoalState.to_string(self.simple_state), rospy.resolve_name(self.action_client.ns)) 00234 00235 if comm_state == CommState.ACTIVE: 00236 if self.simple_state == SimpleGoalState.PENDING: 00237 self._set_simple_state(SimpleGoalState.ACTIVE) 00238 if self.active_cb: 00239 self.active_cb() 00240 elif self.simple_state == SimpleGoalState.DONE: 00241 rospy.logerr(error_msg) 00242 elif comm_state == CommState.RECALLING: 00243 if self.simple_state != SimpleGoalState.PENDING: 00244 rospy.logerr(error_msg) 00245 elif comm_state == CommState.PREEMPTING: 00246 if self.simple_state == SimpleGoalState.PENDING: 00247 self._set_simple_state(SimpleGoalState.ACTIVE) 00248 if self.active_cb: 00249 self.active_cb() 00250 elif self.simple_state == SimpleGoalState.DONE: 00251 rospy.logerr(error_msg) 00252 elif comm_state == CommState.DONE: 00253 if self.simple_state in [SimpleGoalState.PENDING, SimpleGoalState.ACTIVE]: 00254 self._set_simple_state(SimpleGoalState.DONE) 00255 if self.done_cb: 00256 self.done_cb(gh.get_goal_status(), gh.get_result()) 00257 with self.done_condition: 00258 self.done_condition.notifyAll() 00259 elif self.simple_state == SimpleGoalState.DONE: 00260 rospy.logerr("SimpleActionClient received DONE twice") 00261 00262 def _handle_feedback(self, gh, feedback): 00263 if not self.gh: 00264 rospy.logerr("Got a feedback callback when we're not tracking a goal. (id: %s)" % \ 00265 gh.comm_state_machine.action_goal.goal_id.id) 00266 return 00267 if gh != self.gh: 00268 rospy.logerr("Got a feedback callback on a goal handle that we're not tracking. %s vs %s" % \ 00269 (self.gh.comm_state_machine.action_goal.goal_id.id, 00270 gh.comm_state_machine.action_goal.goal_id.id)) 00271 return 00272 if self.feedback_cb: 00273 self.feedback_cb(feedback) 00274 00275 00276 def _set_simple_state(self, state): 00277 self.simple_state = state