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);
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 self.status_frequency = rospy.get_param(rospy.remap_name(self.ns)+"/status_frequency", 5.0);
00152
00153 status_list_timeout = rospy.get_param(rospy.remap_name(self.ns)+"/status_list_timeout", 5.0);
00154 self.status_list_timeout = rospy.Duration(status_list_timeout);
00155
00156
00157 self.status_timer = threading.Thread( None, ros_timer, None, (self.publish_status_async,self.status_frequency) );
00158 self.status_timer.start();
00159
00160
00161
00162
00163 def publish_result(self, status, result):
00164 with self.lock:
00165 ar = self.ActionResult();
00166 ar.header.stamp = rospy.Time.now();
00167 ar.status = status;
00168 ar.result = result;
00169 self.result_pub.publish(ar);
00170
00171
00172
00173
00174
00175 def publish_feedback(self, status, feedback):
00176 with self.lock:
00177
00178 af=self.ActionFeedback();
00179 af.header.stamp = rospy.Time.now();
00180 af.status = status;
00181 af.feedback = feedback;
00182 self.feedback_pub.publish(af);
00183
00184
00185
00186 def internal_cancel_callback(self, goal_id):
00187 with self.lock:
00188
00189
00190 if not self.started:
00191 return;
00192
00193
00194 rospy.logdebug("The action server has received a new cancel request");
00195
00196 goal_id_found = False;
00197 for i, it in enumerate(self.status_list):
00198
00199
00200
00201 cancel_everything = (goal_id.id == "" and goal_id.stamp == rospy.Time() )
00202 cancel_this_one = ( goal_id.id == it.status.goal_id.id)
00203 cancel_before_stamp = (goal_id.stamp != rospy.Time() and it.status.goal_id.stamp <= goal_id.stamp)
00204
00205 if cancel_everything or cancel_this_one or cancel_before_stamp:
00206
00207 if goal_id.id == it.status.goal_id.id:
00208 goal_id_found = True;
00209
00210
00211 handle_tracker = it.handle_tracker;
00212
00213 if handle_tracker is None:
00214
00215 handle_tracker = HandleTrackerDeleter(self, it);
00216 it.handle_tracker = handle_tracker;
00217
00218
00219 it.handle_destruction_time = rospy.Time.now()
00220
00221
00222
00223
00224 gh = ServerGoalHandle(it, self, handle_tracker);
00225 if gh.set_cancel_requested():
00226
00227 self.lock.release()
00228
00229 self.cancel_callback(gh);
00230 self.lock.acquire()
00231
00232
00233
00234 if goal_id.id != "" and not goal_id_found:
00235 tracker= StatusTracker(goal_id, actionlib_msgs.msg.GoalStatus.RECALLING);
00236 self.status_list.append(tracker)
00237
00238 tracker.handle_destruction_time = rospy.Time.now()
00239
00240
00241 if goal_id.stamp > self.last_cancel:
00242 self.last_cancel = goal_id.stamp;
00243
00244
00245
00246 def internal_goal_callback(self, goal):
00247 with self.lock:
00248
00249 if not self.started:
00250 return;
00251
00252 rospy.logdebug("The action server has received a new goal request");
00253
00254
00255 for st in self.status_list:
00256 if goal.goal_id.id == st.status.goal_id.id:
00257 rospy.logdebug("Goal %s was already in the status list with status %i" % (goal.goal_id.id, st.status.status))
00258
00259 if st.status.status == actionlib_msgs.msg.GoalStatus.RECALLING:
00260 st.status.status = actionlib_msgs.msg.GoalStatus.RECALLED
00261 self.publish_result(st.status, self.ActionResultType())
00262
00263
00264
00265 if st.handle_tracker is None:
00266 st.handle_destruction_time = rospy.Time.now()
00267
00268
00269 return;
00270
00271
00272 st = StatusTracker(None,None,goal)
00273 self.status_list.append(st);
00274
00275
00276 handle_tracker = HandleTrackerDeleter(self, st);
00277
00278 st.handle_tracker = handle_tracker;
00279
00280
00281 gh= ServerGoalHandle(st, self, handle_tracker);
00282 if goal.goal_id.stamp != rospy.Time() and goal.goal_id.stamp <= self.last_cancel:
00283
00284 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");
00285 else:
00286
00287 self.lock.release()
00288
00289 self.goal_callback(gh);
00290 self.lock.acquire()
00291
00292
00293
00294 def publish_status_async(self):
00295 rospy.logdebug("Status async");
00296 with self.lock:
00297
00298 if not self.started:
00299 return
00300 self.publish_status();
00301
00302
00303
00304
00305 def publish_status(self):
00306 with self.lock:
00307
00308 status_array = actionlib_msgs.msg.GoalStatusArray()
00309
00310
00311
00312 i=0;
00313 while i<len(self.status_list):
00314 st = self.status_list[i]
00315
00316 if st.handle_destruction_time != rospy.Time() and st.handle_destruction_time + self.status_list_timeout < rospy.Time.now():
00317 rospy.logdebug("Item %s with destruction time of %.3f being removed from list. Now = %.3f" % \
00318 (st.status.goal_id, st.handle_destruction_time.to_sec(), rospy.Time.now().to_sec()))
00319 del self.status_list[i]
00320 else:
00321 status_array.status_list.append(st.status);
00322 i+=1
00323
00324
00325 status_array.header.stamp = rospy.Time.now()
00326 self.status_pub.publish(status_array)
00327
00328