00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031 from __future__ import with_statement
00032
00033 import roslib; roslib.load_manifest('actionlib')
00034 import rospy
00035
00036 import threading
00037 import traceback
00038
00039 from actionlib_msgs.msg import *
00040
00041 from actionlib import ActionServer
00042 from actionlib.server_goal_handle import ServerGoalHandle;
00043
00044 def nop_cb(goal_handle):
00045 pass
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058 class SimpleActionServer:
00059
00060
00061
00062
00063
00064
00065 def __init__(self, name, ActionSpec, execute_cb = None, auto_start = True):
00066
00067 self.new_goal = False
00068 self.preempt_request = False
00069 self.new_goal_preempt_request = False
00070
00071 self.execute_callback = execute_cb;
00072 self.goal_callback = None;
00073 self.preempt_callback = None;
00074
00075 self.need_to_terminate = False
00076 self.terminate_mutex = threading.RLock();
00077 self.lock = threading.RLock();
00078
00079 self.execute_condition = threading.Condition(self.lock);
00080
00081 self.current_goal = ServerGoalHandle();
00082 self.next_goal = ServerGoalHandle();
00083
00084 if self.execute_callback:
00085 self.execute_thread = threading.Thread(None, self.executeLoop);
00086 self.execute_thread.start();
00087 else:
00088 self.execute_thread = None
00089
00090
00091 self.action_server = ActionServer(name, ActionSpec, self.internal_goal_callback,self.internal_preempt_callback,auto_start);
00092
00093
00094 def __del__(self):
00095 if hasattr(self, 'execute_callback') and self.execute_callback:
00096 with self.terminate_mutex:
00097 self.need_to_terminate = True;
00098
00099 assert(self.execute_thread);
00100 self.execute_thread.join();
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112 def accept_new_goal(self):
00113 with self.lock:
00114 if not self.new_goal or not self.next_goal.get_goal():
00115 rospy.logerr("Attempting to accept the next goal when a new goal is not available");
00116 return None;
00117
00118
00119 if self.is_active() and self.current_goal.get_goal() and self.current_goal != self.next_goal:
00120 self.current_goal.set_canceled(None, "This goal was canceled because another goal was received by the simple action server");
00121
00122 rospy.logdebug("Accepting a new goal");
00123
00124
00125 self.current_goal = self.next_goal;
00126 self.new_goal = False;
00127
00128
00129 self.preempt_request = self.new_goal_preempt_request;
00130 self.new_goal_preempt_request = False;
00131
00132
00133 self.current_goal.set_accepted("This goal has been accepted by the simple action server");
00134
00135 return self.current_goal.get_goal();
00136
00137
00138
00139
00140 def is_new_goal_available(self):
00141 return self.new_goal;
00142
00143
00144
00145
00146 def is_preempt_requested(self):
00147 return self.preempt_request;
00148
00149
00150
00151 def is_active(self):
00152 if not self.current_goal.get_goal():
00153 return False;
00154
00155 status = self.current_goal.get_goal_status().status;
00156 return status == actionlib_msgs.msg.GoalStatus.ACTIVE or status == actionlib_msgs.msg.GoalStatus.PREEMPTING;
00157
00158
00159
00160 def set_succeeded(self,result=None, text=""):
00161 with self.lock:
00162 if not result:
00163 result=self.get_default_result();
00164 self.current_goal.set_succeeded(result, text);
00165
00166
00167
00168 def set_aborted(self, result = None, text=""):
00169 with self.lock:
00170 if not result:
00171 result=self.get_default_result();
00172 self.current_goal.set_aborted(result, text);
00173
00174
00175
00176 def publish_feedback(self,feedback):
00177 self.current_goal.publish_feedback(feedback);
00178
00179
00180 def get_default_result(self):
00181 return self.action_server.ActionResultType();
00182
00183
00184
00185 def set_preempted(self,result=None, text=""):
00186 if not result:
00187 result=self.get_default_result();
00188 with self.lock:
00189 rospy.logdebug("Setting the current goal as canceled");
00190 self.current_goal.set_canceled(result, text);
00191
00192
00193
00194 def register_goal_callback(self,cb):
00195 if self.execute_callback:
00196 rospy.logwarn("Cannot call SimpleActionServer.register_goal_callback() because an executeCallback exists. Not going to register it.");
00197 else:
00198 self.goal_callback = cb;
00199
00200
00201
00202 def register_preempt_callback(self, cb):
00203 self.preempt_callback = cb;
00204
00205
00206
00207 def start(self):
00208 self.action_server.start();
00209
00210
00211
00212 def internal_goal_callback(self, goal):
00213 self.execute_condition.acquire();
00214
00215 try:
00216 rospy.logdebug("A new goal %shas been recieved by the single goal action server",goal.get_goal_id().id);
00217
00218
00219 if((not self.current_goal.get_goal() or goal.get_goal_id().stamp >= self.current_goal.get_goal_id().stamp)
00220 and (not self.next_goal.get_goal() or goal.get_goal_id().stamp >= self.next_goal.get_goal_id().stamp)):
00221
00222 if(self.next_goal.get_goal() and (not self.current_goal.get_goal() or self.next_goal != self.current_goal)):
00223 self.next_goal.set_canceled(None, "This goal was canceled because another goal was received by the simple action server");
00224
00225 self.next_goal = goal;
00226 self.new_goal = True;
00227 self.new_goal_preempt_request = False;
00228
00229
00230 if(self.is_active()):
00231 self.preempt_request = True;
00232
00233 if(self.preempt_callback):
00234 self.preempt_callback();
00235
00236
00237 if self.goal_callback:
00238 self.goal_callback();
00239
00240
00241 self.execute_condition.notify();
00242 self.execute_condition.release();
00243 else:
00244
00245 goal.set_canceled(None, "This goal was canceled because another goal was received by the simple action server");
00246 self.execute_condition.release();
00247 except Exception, e:
00248 rospy.logerr("SimpleActionServer.internal_goal_callback - exception %s",str(e))
00249 self.execute_condition.release();
00250
00251
00252 def internal_preempt_callback(self,preempt):
00253 with self.lock:
00254 rospy.logdebug("A preempt has been received by the SimpleActionServer");
00255
00256
00257 if(preempt == self.current_goal):
00258 rospy.logdebug("Setting preempt_request bit for the current goal to TRUE and invoking callback");
00259 self.preempt_request = True;
00260
00261
00262 if(self.preempt_callback):
00263 self.preempt_callback();
00264
00265 elif(preempt == self.next_goal):
00266 rospy.logdebug("Setting preempt request bit for the next goal to TRUE");
00267 self.new_goal_preempt_request = True;
00268
00269
00270 def executeLoop(self):
00271 loop_duration = rospy.Duration.from_sec(.1);
00272
00273 while (not rospy.is_shutdown()):
00274 rospy.logdebug("SAS: execute");
00275
00276 with self.terminate_mutex:
00277 if (self.need_to_terminate):
00278 break;
00279
00280 shall_run=False;
00281 with self.lock:
00282 if (self.is_active()):
00283 rospy.logerr("Should never reach this code with an active goal");
00284 return
00285 elif (self.is_new_goal_available()):
00286 goal = self.accept_new_goal();
00287 if not self.execute_callback:
00288 rospy.logerr("execute_callback_ must exist. This is a bug in SimpleActionServer");
00289 return
00290 shall_run=True
00291
00292 if shall_run:
00293 try:
00294 self.execute_callback(goal)
00295
00296 if self.is_active():
00297 rospy.logwarn("Your executeCallback did not set the goal to a terminal status. " +
00298 "This is a bug in your ActionServer implementation. Fix your code! "+
00299 "For now, the ActionServer will set this goal to aborted");
00300 self.set_aborted(None, "No terminal state was set.");
00301 except Exception, ex:
00302 rospy.logerr("Exception in your execute callback: %s\n%s", str(ex),
00303 traceback.format_exc())
00304 self.set_aborted(None, "Exception in execute callback: %s" % str(ex))
00305
00306 with self.execute_condition:
00307 self.execute_condition.wait(loop_duration.to_sec());
00308
00309
00310