41 from actionlib
import ActionServer
58 def __init__(self, name, ActionSpec, execute_cb = None, auto_start = True):
75 self.
lock = threading.RLock();
84 self.execute_thread.start();
99 self.execute_thread.join();
105 with self.action_server.lock, self.
lock:
107 rospy.logdebug(
"Accepting a new goal");
112 current_goal = self.goal_queue_.get()
115 current_goal.set_accepted(
"This goal has been accepted by the simple action server");
129 if not self.current_goal.get_goal():
132 status = self.current_goal.get_goal_status().status;
133 return status == actionlib_msgs.msg.GoalStatus.ACTIVE
138 with self.action_server.lock, self.
lock:
142 goal_handle.set_succeeded(result,text)
147 with self.action_server.lock, self.
lock:
151 goal_handle.set_aborted(result,text)
156 self.current_goal.publish_feedback(feedback);
160 return self.action_server.ActionResultType();
166 rospy.logwarn(
"Cannot call ComplexActionServer.register_goal_callback() because an executeCallback exists. Not going to register it.");
173 self.action_server.start();
178 self.execute_condition.acquire();
181 rospy.logdebug(
"A new goal %shas been recieved by the single goal action server",goal.get_goal_id().id);
190 self.goal_queue_.put(goal)
193 self.execute_condition.notify();
194 self.execute_condition.release();
197 rospy.logerr(
"ComplexActionServer.internal_goal_callback - exception %s",str(e))
198 self.execute_condition.release();
207 loop_duration = rospy.Duration.from_sec(.1);
209 while (
not rospy.is_shutdown()):
210 rospy.logdebug(
"SAS: execute");
220 rospy.logerr(
"execute_callback_ must exist. This is a bug in ComplexActionServer");
225 print "run new executecb" 226 thread = threading.Thread(target=self.
run_goal,args=(goal_handle.get_goal(),goal_handle));
229 except Exception, ex:
230 rospy.logerr(
"Exception in your execute callback: %s\n%s", str(ex),
231 traceback.format_exc())
232 self.
set_aborted(
None,
"Exception in execute callback: %s" % str(ex))
235 self.execute_condition.wait(loop_duration.to_sec());