Go to the documentation of this file.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
00032 import rospy
00033
00034 import threading
00035 import traceback
00036
00037 import Queue
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 class ComplexActionServer:
00052
00053
00054
00055
00056
00057
00058 def __init__(self, name, ActionSpec, execute_cb = None, auto_start = True):
00059
00060 self.goals_received_ = 0;
00061 self.goal_queue_ = Queue.Queue()
00062
00063 self.new_goal = False
00064
00065 self.execute_callback = execute_cb;
00066 self.goal_callback = None;
00067
00068 self.need_to_terminate = False
00069 self.terminate_mutex = threading.RLock();
00070
00071
00072
00073
00074
00075 self.lock = threading.RLock();
00076
00077 self.execute_condition = threading.Condition(self.lock);
00078
00079 self.current_goal = ServerGoalHandle();
00080 self.next_goal = ServerGoalHandle();
00081
00082 if self.execute_callback:
00083 self.execute_thread = threading.Thread(None, self.executeLoop);
00084 self.execute_thread.start();
00085 else:
00086 self.execute_thread = None
00087
00088
00089
00090 self.action_server = ActionServer(name, ActionSpec, self.internal_goal_callback,self.internal_preempt_callback,auto_start);
00091
00092
00093 def __del__(self):
00094 if hasattr(self, 'execute_callback') and self.execute_callback:
00095 with self.terminate_mutex:
00096 self.need_to_terminate = True;
00097
00098 assert(self.execute_thread);
00099 self.execute_thread.join();
00100
00101
00102
00103
00104 def accept_new_goal(self):
00105 with self.action_server.lock, self.lock:
00106
00107 rospy.logdebug("Accepting a new goal");
00108
00109 self.goals_received_ -= 1;
00110
00111
00112 current_goal = self.goal_queue_.get()
00113
00114
00115 current_goal.set_accepted("This goal has been accepted by the simple action server");
00116
00117 return current_goal
00118
00119
00120
00121
00122 def is_new_goal_available(self):
00123 return self.goals_received_ > 0
00124
00125
00126
00127
00128 def is_active(self):
00129 if not self.current_goal.get_goal():
00130 return False;
00131
00132 status = self.current_goal.get_goal_status().status;
00133 return status == actionlib_msgs.msg.GoalStatus.ACTIVE
00134
00135
00136
00137 def set_succeeded(self,result=None, text="", goal_handle=None):
00138 with self.action_server.lock, self.lock:
00139 if not result:
00140 result=self.get_default_result();
00141
00142 goal_handle.set_succeeded(result,text)
00143
00144
00145
00146 def set_aborted(self, result = None, text="" , goal_handle=None):
00147 with self.action_server.lock, self.lock:
00148 if not result:
00149 result=self.get_default_result();
00150
00151 goal_handle.set_aborted(result,text)
00152
00153
00154
00155 def publish_feedback(self,feedback):
00156 self.current_goal.publish_feedback(feedback);
00157
00158
00159 def get_default_result(self):
00160 return self.action_server.ActionResultType();
00161
00162
00163
00164 def register_goal_callback(self,cb):
00165 if self.execute_callback:
00166 rospy.logwarn("Cannot call ComplexActionServer.register_goal_callback() because an executeCallback exists. Not going to register it.");
00167 else:
00168 self.goal_callback = cb;
00169
00170
00171
00172 def start(self):
00173 self.action_server.start();
00174
00175
00176
00177 def internal_goal_callback(self, goal):
00178 self.execute_condition.acquire();
00179
00180 try:
00181 rospy.logdebug("A new goal %shas been recieved by the single goal action server",goal.get_goal_id().id);
00182
00183
00184 print "got a goal"
00185 self.next_goal = goal;
00186 self.new_goal = True;
00187 self.goals_received_ += 1
00188
00189
00190 self.goal_queue_.put(goal)
00191
00192
00193 self.execute_condition.notify();
00194 self.execute_condition.release();
00195
00196 except Exception, e:
00197 rospy.logerr("ComplexActionServer.internal_goal_callback - exception %s",str(e))
00198 self.execute_condition.release();
00199
00200
00201
00202 def internal_preempt_callback(self,preempt):
00203 return
00204
00205
00206 def executeLoop(self):
00207 loop_duration = rospy.Duration.from_sec(.1);
00208
00209 while (not rospy.is_shutdown()):
00210 rospy.logdebug("SAS: execute");
00211
00212 with self.terminate_mutex:
00213 if (self.need_to_terminate):
00214 break;
00215
00216 if (self.is_new_goal_available()):
00217
00218 goal_handle = self.accept_new_goal();
00219 if not self.execute_callback:
00220 rospy.logerr("execute_callback_ must exist. This is a bug in ComplexActionServer");
00221 return
00222
00223 try:
00224
00225 print "run new executecb"
00226 thread = threading.Thread(target=self.run_goal,args=(goal_handle.get_goal(),goal_handle));
00227 thread.start()
00228
00229 except Exception, ex:
00230 rospy.logerr("Exception in your execute callback: %s\n%s", str(ex),
00231 traceback.format_exc())
00232 self.set_aborted(None, "Exception in execute callback: %s" % str(ex))
00233
00234 with self.execute_condition:
00235 self.execute_condition.wait(loop_duration.to_sec());
00236
00237
00238
00239
00240 def run_goal(self,goal, goal_handle):
00241 print 'new thread'
00242 self.execute_callback(goal,goal_handle);
00243
00244
00245