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
00038 from actionlib_msgs.msg import *
00039
00040 from goal_id_generator import GoalIDGenerator
00041 from status_tracker import StatusTracker
00042
00043 from handle_tracker_deleter import HandleTrackerDeleter
00044 from server_goal_handle import ServerGoalHandle
00045
00046 from actionlib.exceptions import *
00047
00048
00049 def nop_cb(goal_handle):
00050 pass
00051
00052 def ros_timer(callable,frequency):
00053 rate = rospy.Rate(frequency)
00054
00055 rospy.logdebug("Starting timer");
00056 while not rospy.is_shutdown():
00057 try:
00058 rate.sleep()
00059 callable()
00060 except rospy.exceptions.ROSInterruptException:
00061 rospy.logdebug("Sleep interrupted");
00062
00063
00064
00065
00066
00067
00068
00069
00070
00071 class ActionServer:
00072
00073
00074
00075
00076
00077
00078 def __init__(self, ns, ActionSpec, goal_cb, cancel_cb = nop_cb, auto_start = True):
00079 self.ns=ns;
00080
00081 try:
00082 a = ActionSpec()
00083
00084 self.ActionSpec = ActionSpec
00085 self.ActionGoal = type(a.action_goal)
00086 self.ActionResult = type(a.action_result)
00087 self.ActionResultType = type(a.action_result.result)
00088 self.ActionFeedback = type(a.action_feedback)
00089 except AttributeError:
00090 raise ActionException("Type is not an action spec: %s" % str(ActionSpec))
00091
00092
00093 self.goal_sub = None
00094 self.cancel_sub = None
00095 self.status_pub = None
00096 self.result_pub = None
00097 self.feedback_pub = None
00098
00099 self.lock = threading.RLock()
00100
00101 self.status_timer = None;
00102
00103 self.status_list = [];
00104
00105 self.last_cancel = rospy.Time();
00106 self.status_list_timeout = rospy.Duration();
00107
00108 self.id_generator = GoalIDGenerator();
00109
00110 self.goal_callback = goal_cb;
00111 assert(self.goal_callback);
00112
00113 self.cancel_callback = cancel_cb;
00114 self.auto_start = auto_start;
00115
00116 self.started = False;
00117
00118 if self.auto_start:
00119 rospy.logwarn("You've passed in true for auto_start to the python action server, you should always pass in false to avoid race conditions.")
00120 self.start()
00121
00122
00123
00124
00125 def register_goal_callback(self, cb):
00126 self.goal_callback = cb
00127
00128
00129
00130 def register_cancel_callback(self,cancel_cb):
00131 self.cancel_callback = cancel_cb
00132
00133
00134 def start(self):
00135 with self.lock:
00136 self.initialize();
00137 self.started = True;
00138 self.publish_status();
00139
00140
00141 def initialize(self):
00142 self.status_pub = rospy.Publisher(rospy.remap_name(self.ns)+"/status", GoalStatusArray, latch=True);
00143 self.result_pub = rospy.Publisher(rospy.remap_name(self.ns)+"/result", self.ActionResult);
00144 self.feedback_pub = rospy.Publisher(rospy.remap_name(self.ns)+"/feedback", self.ActionFeedback);
00145
00146 self.goal_sub = rospy.Subscriber(rospy.remap_name(self.ns)+"/goal", self.ActionGoal,self.internal_goal_callback);
00147
00148 self.cancel_sub = rospy.Subscriber(rospy.remap_name(self.ns)+"/cancel", GoalID,self.internal_cancel_callback);
00149
00150
00151
00152 resolved_status_frequency_name = rospy.remap_name(self.ns)+"/status_frequency"
00153 if rospy.has_param(resolved_status_frequency_name):
00154 self.status_frequency = rospy.get_param(resolved_status_frequency_name, 5.0);
00155 rospy.logwarn("You're using the deprecated status_frequency parameter, please switch to actionlib_status_frequency.")
00156 else:
00157 search_status_frequency_name = rospy.search_param("actionlib_status_frequency")
00158 if search_status_frequency_name is None:
00159 self.status_frequency = 5.0
00160 else:
00161 self.status_frequency = rospy.get_param(search_status_frequency_name, 5.0)
00162
00163 status_list_timeout = rospy.get_param(rospy.remap_name(self.ns)+"/status_list_timeout", 5.0);
00164 self.status_list_timeout = rospy.Duration(status_list_timeout);
00165
00166
00167 self.status_timer = threading.Thread( None, ros_timer, None, (self.publish_status_async,self.status_frequency) );
00168 self.status_timer.start();
00169
00170
00171
00172
00173 def publish_result(self, status, result):
00174 with self.lock:
00175 ar = self.ActionResult();
00176 ar.header.stamp = rospy.Time.now();
00177 ar.status = status;
00178 ar.result = result;
00179 self.result_pub.publish(ar);
00180 self.publish_status()
00181
00182
00183
00184
00185
00186 def publish_feedback(self, status, feedback):
00187 with self.lock:
00188
00189 af=self.ActionFeedback();
00190 af.header.stamp = rospy.Time.now();
00191 af.status = status;
00192 af.feedback = feedback;
00193 self.feedback_pub.publish(af);
00194
00195
00196
00197 def internal_cancel_callback(self, goal_id):
00198 with self.lock:
00199
00200
00201 if not self.started:
00202 return;
00203
00204
00205 rospy.logdebug("The action server has received a new cancel request");
00206
00207 goal_id_found = False;
00208 for i, it in enumerate(self.status_list):
00209
00210
00211
00212 cancel_everything = (goal_id.id == "" and goal_id.stamp == rospy.Time() )
00213 cancel_this_one = ( goal_id.id == it.status.goal_id.id)
00214 cancel_before_stamp = (goal_id.stamp != rospy.Time() and it.status.goal_id.stamp <= goal_id.stamp)
00215
00216 if cancel_everything or cancel_this_one or cancel_before_stamp:
00217
00218 if goal_id.id == it.status.goal_id.id:
00219 goal_id_found = True;
00220
00221
00222 handle_tracker = it.handle_tracker;
00223
00224 if handle_tracker is None:
00225
00226 handle_tracker = HandleTrackerDeleter(self, it);
00227 it.handle_tracker = handle_tracker;
00228
00229
00230 it.handle_destruction_time = rospy.Time.now()
00231
00232
00233
00234
00235 gh = ServerGoalHandle(it, self, handle_tracker);
00236 if gh.set_cancel_requested():
00237
00238 self.lock.release()
00239
00240 self.cancel_callback(gh);
00241 self.lock.acquire()
00242
00243
00244
00245 if goal_id.id != "" and not goal_id_found:
00246 tracker= StatusTracker(goal_id, actionlib_msgs.msg.GoalStatus.RECALLING);
00247 self.status_list.append(tracker)
00248
00249 tracker.handle_destruction_time = rospy.Time.now()
00250
00251
00252 if goal_id.stamp > self.last_cancel:
00253 self.last_cancel = goal_id.stamp;
00254
00255
00256
00257 def internal_goal_callback(self, goal):
00258 with self.lock:
00259
00260 if not self.started:
00261 return;
00262
00263 rospy.logdebug("The action server has received a new goal request");
00264
00265
00266 for st in self.status_list:
00267 if goal.goal_id.id == st.status.goal_id.id:
00268 rospy.logdebug("Goal %s was already in the status list with status %i" % (goal.goal_id.id, st.status.status))
00269
00270 if st.status.status == actionlib_msgs.msg.GoalStatus.RECALLING:
00271 st.status.status = actionlib_msgs.msg.GoalStatus.RECALLED
00272 self.publish_result(st.status, self.ActionResultType())
00273
00274
00275
00276 if st.handle_tracker is None:
00277 st.handle_destruction_time = rospy.Time.now()
00278
00279
00280 return;
00281
00282
00283 st = StatusTracker(None,None,goal)
00284 self.status_list.append(st);
00285
00286
00287 handle_tracker = HandleTrackerDeleter(self, st);
00288
00289 st.handle_tracker = handle_tracker;
00290
00291
00292 gh= ServerGoalHandle(st, self, handle_tracker);
00293 if goal.goal_id.stamp != rospy.Time() and goal.goal_id.stamp <= self.last_cancel:
00294
00295 gh.set_canceled(None, "This goal handle was canceled by the action server because its timestamp is before the timestamp of the last cancel request");
00296 else:
00297
00298 self.lock.release()
00299
00300 self.goal_callback(gh);
00301 self.lock.acquire()
00302
00303
00304
00305 def publish_status_async(self):
00306 rospy.logdebug("Status async");
00307 with self.lock:
00308
00309 if not self.started:
00310 return
00311 self.publish_status();
00312
00313
00314
00315
00316 def publish_status(self):
00317 with self.lock:
00318
00319 status_array = actionlib_msgs.msg.GoalStatusArray()
00320
00321
00322
00323 i=0;
00324 while i<len(self.status_list):
00325 st = self.status_list[i]
00326
00327 if st.handle_destruction_time != rospy.Time() and st.handle_destruction_time + self.status_list_timeout < rospy.Time.now():
00328 rospy.logdebug("Item %s with destruction time of %.3f being removed from list. Now = %.3f" % \
00329 (st.status.goal_id, st.handle_destruction_time.to_sec(), rospy.Time.now().to_sec()))
00330 del self.status_list[i]
00331 else:
00332 status_array.status_list.append(st.status);
00333 i+=1
00334
00335
00336 status_array.header.stamp = rospy.Time.now()
00337 self.status_pub.publish(status_array)
00338
00339