40 from actionlib
import ActionServer
57 def __init__(self, name, ActionSpec, execute_cb = None, auto_start = True):
74 self.
lock = threading.RLock();
83 self.execute_thread.start();
98 self.execute_thread.join();
104 with self.action_server.lock, self.
lock:
106 rospy.logdebug(
"Accepting a new goal");
111 current_goal = self.goal_queue_.get()
114 current_goal.set_accepted(
"This goal has been accepted by the simple action server");
128 if not self.current_goal.get_goal():
131 status = self.current_goal.get_goal_status().status;
132 return status == actionlib_msgs.msg.GoalStatus.ACTIVE
137 with self.action_server.lock, self.
lock:
141 goal_handle.set_succeeded(result,text)
146 with self.action_server.lock, self.
lock:
150 goal_handle.set_aborted(result,text)
155 self.current_goal.publish_feedback(feedback);
159 return self.action_server.ActionResultType();
165 rospy.logwarn(
"Cannot call ComplexActionServer.register_goal_callback() because an executeCallback exists. Not going to register it.");
172 self.action_server.start();
177 self.execute_condition.acquire();
180 rospy.logdebug(
"A new goal %shas been recieved by the single goal action server",goal.get_goal_id().id);
189 self.goal_queue_.put(goal)
192 self.execute_condition.notify();
193 self.execute_condition.release();
195 except Exception
as e:
196 rospy.logerr(
"ComplexActionServer.internal_goal_callback - exception %s",str(e))
197 self.execute_condition.release();
206 loop_duration = rospy.Duration.from_sec(.1);
208 while (
not rospy.is_shutdown()):
209 rospy.logdebug(
"SAS: execute");
219 rospy.logerr(
"execute_callback_ must exist. This is a bug in ComplexActionServer");
224 print(
"run new executecb")
225 thread = threading.Thread(target=self.
run_goal,args=(goal_handle.get_goal(),goal_handle));
228 except Exception
as ex:
229 rospy.logerr(
"Exception in your execute callback: %s\n%s", str(ex),
230 traceback.format_exc())
231 self.
set_aborted(
None,
"Exception in execute callback: %s" % str(ex))
234 self.execute_condition.wait(loop_duration.to_sec());