$search
00001 # Copyright (c) 2009, Willow Garage, Inc. 00002 # All rights reserved. 00003 # 00004 # Redistribution and use in source and binary forms, with or without 00005 # modification, are permitted provided that the following conditions are met: 00006 # 00007 # * Redistributions of source code must retain the above copyright 00008 # notice, this list of conditions and the following disclaimer. 00009 # * Redistributions in binary form must reproduce the above copyright 00010 # notice, this list of conditions and the following disclaimer in the 00011 # documentation and/or other materials provided with the distribution. 00012 # * Neither the name of the Willow Garage, Inc. nor the names of its 00013 # contributors may be used to endorse or promote products derived from 00014 # this software without specific prior written permission. 00015 # 00016 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00017 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00018 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00019 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00020 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00021 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00022 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00023 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00024 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00025 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00026 # POSSIBILITY OF SUCH DAMAGE. 00027 00028 # Author: Alexander Sorokin. 00029 # Based on C++ goal_id_generator.h/cpp 00030 from __future__ import with_statement 00031 import roslib; roslib.load_manifest('actionlib') 00032 00033 import rospy 00034 00035 import actionlib_msgs.msg 00036 00037 class ServerGoalHandle: 00038 """ 00039 * @class ServerGoalHandle 00040 * @brief Encapsulates a state machine for a given goal that the user can 00041 * trigger transisions on. All ROS interfaces for the goal are managed by 00042 * the ActionServer to lessen the burden on the user. 00043 00044 """ 00045 00046 def __init__(self, status_tracker=None, action_server=None, handle_tracker=None): 00047 """ 00048 A private constructor used by the ActionServer to initialize a ServerGoalHandle. 00049 @node The default constructor was not ported. 00050 """ 00051 self.status_tracker = status_tracker; 00052 self.action_server = action_server 00053 self.handle_tracker = handle_tracker; 00054 00055 if status_tracker: 00056 self.goal=status_tracker.goal; 00057 else: 00058 self.goal=None 00059 00060 00061 def get_default_result(self): 00062 return self.action_server.ActionResultType(); 00063 00064 def set_accepted(self, text=""): 00065 """ 00066 Accept the goal referenced by the goal handle. This will 00067 transition to the ACTIVE state or the PREEMPTING state depending 00068 on whether a cancel request has been received for the goal 00069 """ 00070 00071 rospy.logdebug("Accepting goal, id: %s, stamp: %.2f", self.get_goal_id().id, self.get_goal_id().stamp.to_sec()); 00072 if self.goal: 00073 with self.action_server.lock: 00074 status = self.status_tracker.status.status; 00075 00076 #if we were pending before, then we'll go active 00077 if(status == actionlib_msgs.msg.GoalStatus.PENDING): 00078 self.status_tracker.status.status = actionlib_msgs.msg.GoalStatus.ACTIVE; 00079 self.status_tracker.status.text = text 00080 self.action_server.publish_status(); 00081 00082 #if we were recalling before, now we'll go to preempting 00083 elif(status == actionlib_msgs.msg.GoalStatus.RECALLING) : 00084 self.status_tracker.status.status = actionlib_msgs.msg.GoalStatus.PREEMPTING; 00085 self.status_tracker.status.text = text 00086 self.action_server.publish_status(); 00087 00088 else: 00089 rospy.logerr("To transition to an active state, the goal must be in a pending or recalling state, it is currently in state: %d", self.status_tracker.status.status); 00090 00091 else: 00092 rospy.logerr("Attempt to set status on an uninitialized ServerGoalHandle"); 00093 00094 00095 def set_canceled(self, result=None, text=""): 00096 """ 00097 Set the status of the goal associated with the ServerGoalHandle to RECALLED or PREEMPTED 00098 depending on what the current status of the goal is 00099 @param result Optionally, the user can pass in a result to be sent to any clients of the goal 00100 """ 00101 if not result: 00102 result=self.get_default_result(); 00103 00104 rospy.logdebug("Setting status to canceled on goal, id: %s, stamp: %.2f", self.get_goal_id().id, self.get_goal_id().stamp.to_sec()); 00105 00106 if(self.goal): 00107 with self.action_server.lock: 00108 status = self.status_tracker.status.status; 00109 if(status == actionlib_msgs.msg.GoalStatus.PENDING or status == actionlib_msgs.msg.GoalStatus.RECALLING): 00110 self.status_tracker.status.status = actionlib_msgs.msg.GoalStatus.RECALLED; 00111 self.status_tracker.status.text = text 00112 #on transition to a terminal state, we'll also set the handle destruction time 00113 self.status_tracker.handle_destruction_time = rospy.Time.now() 00114 self.action_server.publish_result(self.status_tracker.status, result); 00115 elif(status == actionlib_msgs.msg.GoalStatus.ACTIVE or status == actionlib_msgs.msg.GoalStatus.PREEMPTING): 00116 self.status_tracker.status.status = actionlib_msgs.msg.GoalStatus.PREEMPTED; 00117 self.status_tracker.status.text = text 00118 #on transition to a terminal state, we'll also set the handle destruction time 00119 self.status_tracker.handle_destruction_time = rospy.Time.now() 00120 self.action_server.publish_result(self.status_tracker.status, result); 00121 00122 else: 00123 rospy.logerr("To transition to a cancelled state, the goal must be in a pending, recalling, active, or preempting state, it is currently in state: %d", 00124 self.status_tracker.status.status); 00125 00126 else: 00127 rospy.logerr("Attempt to set status on an uninitialized ServerGoalHandle"); 00128 00129 00130 def set_rejected(self, result=None, text=""): 00131 """ 00132 * @brief Set the status of the goal associated with the ServerGoalHandle to rejected 00133 * @param result Optionally, the user can pass in a result to be sent to any clients of the goal 00134 """ 00135 if not result: 00136 result=self.get_default_result(); 00137 00138 rospy.logdebug("Setting status to rejected on goal, id: %s, stamp: %.2f", self.get_goal_id().id, self.get_goal_id().stamp.to_sec()); 00139 if self.goal : 00140 with self.action_server.lock: 00141 status = self.status_tracker.status.status; 00142 if(status == actionlib_msgs.msg.GoalStatus.PENDING or status == actionlib_msgs.msg.GoalStatus.RECALLING): 00143 self.status_tracker.status.status = actionlib_msgs.msg.GoalStatus.REJECTED; 00144 self.status_tracker.status.text = text 00145 #on transition to a terminal state, we'll also set the handle destruction time 00146 self.status_tracker.handle_destruction_time = rospy.Time.now() 00147 self.action_server.publish_result(self.status_tracker.status, result); 00148 00149 else: 00150 rospy.logerr("To transition to a rejected state, the goal must be in a pending or recalling state, it is currently in state: %d", 00151 self.status_tracker.status.status); 00152 00153 else: 00154 rospy.logerr("Attempt to set status on an uninitialized ServerGoalHandle"); 00155 00156 00157 def set_aborted(self, result=None, text=""): 00158 """ 00159 Set the status of the goal associated with the ServerGoalHandle to aborted 00160 @param result Optionally, the user can pass in a result to be sent to any clients of the goal 00161 """ 00162 if not result: 00163 result=self.get_default_result(); 00164 00165 rospy.logdebug("Setting status to aborted on goal, id: %s, stamp: %.2f", self.get_goal_id().id, self.get_goal_id().stamp.to_sec()); 00166 if self.goal: 00167 with self.action_server.lock: 00168 status = self.status_tracker.status.status; 00169 if status == actionlib_msgs.msg.GoalStatus.PREEMPTING or status == actionlib_msgs.msg.GoalStatus.ACTIVE: 00170 self.status_tracker.status.status = actionlib_msgs.msg.GoalStatus.ABORTED; 00171 self.status_tracker.status.text = text 00172 #on transition to a terminal state, we'll also set the handle destruction time 00173 self.status_tracker.handle_destruction_time = rospy.Time.now() 00174 self.action_server.publish_result(self.status_tracker.status, result); 00175 00176 else: 00177 rospy.logerr("To transition to an aborted state, the goal must be in a preempting or active state, it is currently in state: %d", 00178 status); 00179 00180 else: 00181 rospy.logerr("Attempt to set status on an uninitialized ServerGoalHandle"); 00182 00183 00184 def set_succeeded(self,result=None, text=""): 00185 """ 00186 Set the status of the goal associated with the ServerGoalHandle to succeeded 00187 @param result Optionally, the user can pass in a result to be sent to any clients of the goal 00188 """ 00189 if not result: 00190 result=self.get_default_result(); 00191 00192 rospy.logdebug("Setting status to succeeded on goal, id: %s, stamp: %.2f", 00193 self.get_goal_id().id, self.get_goal_id().stamp.to_sec()); 00194 if self.goal: 00195 with self.action_server.lock: 00196 status = self.status_tracker.status.status; 00197 if status == actionlib_msgs.msg.GoalStatus.PREEMPTING or status == actionlib_msgs.msg.GoalStatus.ACTIVE : 00198 self.status_tracker.status.status = actionlib_msgs.msg.GoalStatus.SUCCEEDED; 00199 self.status_tracker.status.text = text 00200 #on transition to a terminal state, we'll also set the handle destruction time 00201 self.status_tracker.handle_destruction_time = rospy.Time.now() 00202 self.action_server.publish_result(self.status_tracker.status, result); 00203 00204 else: 00205 rospy.logerr("To transition to a succeeded state, the goal must be in a preempting or active state, it is currently in state: %d", 00206 status); 00207 00208 else: 00209 rospy.logerr("Attempt to set status on an uninitialized ServerGoalHandle"); 00210 00211 00212 def publish_feedback(self,feedback): 00213 """ 00214 Send feedback to any clients of the goal associated with this ServerGoalHandle 00215 @param feedback The feedback to send to the client 00216 """ 00217 rospy.logdebug("Publishing feedback for goal, id: %s, stamp: %.2f", 00218 self.get_goal_id().id, self.get_goal_id().stamp.to_sec()); 00219 if self.goal: 00220 with self.action_server.lock: 00221 self.action_server.publish_feedback(self.status_tracker.status, feedback); 00222 else: 00223 rospy.logerr("Attempt to publish feedback on an uninitialized ServerGoalHandle"); 00224 00225 00226 def get_goal(self): 00227 """ 00228 Accessor for the goal associated with the ServerGoalHandle 00229 @return A shared_ptr to the goal object 00230 """ 00231 #if we have a goal that is non-null 00232 if self.goal: 00233 #@todo Test that python reference counting automatically handles this. 00234 #create the deleter for our goal subtype 00235 #d = EnclosureDeleter(self.goal); 00236 #weakref.ref(boost::shared_ptr<const Goal>(&(goal_->goal), d); 00237 return self.goal.goal 00238 00239 return None 00240 00241 00242 def get_goal_id(self): 00243 """ 00244 Accessor for the goal id associated with the ServerGoalHandle 00245 @return The goal id 00246 """ 00247 if self.goal: 00248 with self.action_server.lock: 00249 return self.status_tracker.status.goal_id; 00250 else: 00251 rospy.logerr("Attempt to get a goal id on an uninitialized ServerGoalHandle"); 00252 return actionlib_msgs.msg.GoalID(); 00253 00254 00255 def get_goal_status(self): 00256 """ 00257 Accessor for the status associated with the ServerGoalHandle 00258 @return The goal status 00259 """ 00260 if self.goal: 00261 with self.action_server.lock: 00262 return self.status_tracker.status; 00263 else: 00264 rospy.logerr("Attempt to get goal status on an uninitialized ServerGoalHandle"); 00265 return actionlib_msgs.msg.GoalStatus(); 00266 00267 00268 def __eq__(self, other): 00269 """ 00270 Equals operator for ServerGoalHandles 00271 @param other The ServerGoalHandle to compare to 00272 @return True if the ServerGoalHandles refer to the same goal, false otherwise 00273 """ 00274 00275 if( not self.goal or not other.goal): 00276 return False; 00277 my_id = self.get_goal_id(); 00278 their_id = other.get_goal_id(); 00279 return my_id.id == their_id.id; 00280 00281 def __ne__(self, other): 00282 """ 00283 != operator for ServerGoalHandles 00284 @param other The ServerGoalHandle to compare to 00285 @return True if the ServerGoalHandles refer to different goals, false otherwise 00286 """ 00287 if( not self.goal or not other.goal): 00288 return True; 00289 my_id = self.get_goal_id(); 00290 their_id = other.get_goal_id(); 00291 00292 return my_id.id != their_id.id; 00293 00294 00295 def set_cancel_requested(self): 00296 """ 00297 A private method to set status to PENDING or RECALLING 00298 @return True if the cancel request should be passed on to the user, false otherwise 00299 """ 00300 rospy.logdebug("Transisitoning to a cancel requested state on goal id: %s, stamp: %.2f", 00301 self.get_goal_id().id, self.get_goal_id().stamp.to_sec()); 00302 if self.goal: 00303 with self.action_server.lock: 00304 status = self.status_tracker.status.status; 00305 if (status == actionlib_msgs.msg.GoalStatus.PENDING): 00306 self.status_tracker.status.status = actionlib_msgs.msg.GoalStatus.RECALLING; 00307 self.action_server.publish_status(); 00308 return True; 00309 00310 if(status == actionlib_msgs.msg.GoalStatus.ACTIVE): 00311 self.status_tracker.status.status = actionlib_msgs.msg.GoalStatus.PREEMPTING; 00312 self.action_server.publish_status(); 00313 return True; 00314 00315 return False; 00316 00317 00318 00319 00320 00321 00322 00323 00324 00325 00326