35 from actionlib_msgs.msg
import GoalStatus
37 from actionlib
import ActionServer
62 def __init__(self, name, ActionSpec, execute_cb=None, auto_start=True):
79 self.
lock = threading.RLock()
88 self.execute_thread.start()
101 self.execute_thread.join()
113 with self.action_server.lock, self.
lock:
114 if not self.
new_goal or not self.next_goal.get_goal():
115 rospy.logerr(
"Attempting to accept the next goal when a new goal is not available")
120 self.current_goal.set_canceled(
None,
"This goal was canceled because another goal was received by the simple action server")
122 rospy.logdebug(
"Accepting a new goal")
133 self.current_goal.set_accepted(
"This goal has been accepted by the simple action server")
135 return self.current_goal.get_goal()
150 if not self.current_goal.get_goal():
153 status = self.current_goal.get_goal_status().status
154 return status == GoalStatus.ACTIVE
or status == GoalStatus.PREEMPTING
159 with self.action_server.lock, self.
lock:
162 self.current_goal.set_succeeded(result, text)
167 with self.action_server.lock, self.
lock:
170 self.current_goal.set_aborted(result, text)
175 self.current_goal.publish_feedback(feedback)
178 return self.action_server.ActionResultType()
185 with self.action_server.lock, self.
lock:
186 rospy.logdebug(
"Setting the current goal as canceled")
187 self.current_goal.set_canceled(result, text)
193 rospy.logwarn(
"Cannot call SimpleActionServer.register_goal_callback() because an executeCallback exists. Not going to register it.")
204 self.action_server.start()
208 self.execute_condition.acquire()
211 rospy.logdebug(
"A new goal %shas been received by the single goal action server", goal.get_goal_id().id)
214 if((
not self.current_goal.get_goal()
or goal.get_goal_id().stamp >= self.current_goal.get_goal_id().stamp)
215 and (
not self.next_goal.get_goal()
or goal.get_goal_id().stamp >= self.next_goal.get_goal_id().stamp)):
217 if(self.next_goal.get_goal()
and (
not self.current_goal.get_goal()
or self.
next_goal != self.
current_goal)):
218 self.next_goal.set_canceled(
None,
"This goal was canceled because another goal was received by the simple action server")
236 self.execute_condition.notify()
237 self.execute_condition.release()
240 goal.set_canceled(
None,
"This goal was canceled because another goal was received by the simple action server")
241 self.execute_condition.release()
242 except Exception
as e:
243 rospy.logerr(
"SimpleActionServer.internal_goal_callback - exception %s", str(e))
244 self.execute_condition.release()
249 rospy.logdebug(
"A preempt has been received by the SimpleActionServer")
253 rospy.logdebug(
"Setting preempt_request bit for the current goal to TRUE and invoking callback")
261 rospy.logdebug(
"Setting preempt request bit for the next goal to TRUE")
266 loop_duration = rospy.Duration.from_sec(.1)
268 while (
not rospy.is_shutdown()):
278 rospy.logerr(
"Should never reach this code with an active goal")
285 rospy.logerr(
"execute_callback_ must exist. This is a bug in SimpleActionServer")
292 rospy.logwarn(
"Your executeCallback did not set the goal to a terminal status. " +
293 "This is a bug in your ActionServer implementation. Fix your code! " +
294 "For now, the ActionServer will set this goal to aborted")
295 self.
set_aborted(
None,
"No terminal state was set.")
296 except Exception
as ex:
297 rospy.logerr(
"Exception in your execute callback: %s\n%s", str(ex),
298 traceback.format_exc())
299 self.
set_aborted(
None,
"Exception in execute callback: %s" % str(ex))
302 self.execute_condition.wait(loop_duration.to_sec())
def is_preempt_requested(self)
Allows polling implementations to query about preempt requests.
def accept_new_goal(self)
Accepts a new goal when one is available The status of this goal is set to active upon acceptance...
def internal_preempt_callback(self, preempt)
Callback for when the ActionServer receives a new preempt and passes it on.
def internal_goal_callback(self, goal)
Callback for when the ActionServer receives a new goal and passes it on.
def register_goal_callback(self, cb)
Allows users to register a callback to be invoked when a new goal is available.
def is_active(self)
Allows polling implementations to query about the status of the current goal.
def set_aborted(self, result=None, text="")
Sets the status of the active goal to aborted.
def publish_feedback(self, feedback)
Publishes feedback for a given goal.
def set_succeeded(self, result=None, text="")
Sets the status of the active goal to succeeded.
def set_preempted(self, result=None, text="")
Sets the status of the active goal to preempted.
def register_preempt_callback(self, cb)
Allows users to register a callback to be invoked when a new preempt request is available.
def is_new_goal_available(self)
Allows polling implementations to query about the availability of a new goal.
def start(self)
Explicitly start the action server, used it auto_start is set to false.
The ActionServer is a helpful tool for managing goal requests to a node. It allows the user to specif...
def __init__(self, name, ActionSpec, execute_cb=None, auto_start=True)
Constructor for a SimpleActionServer.
The SimpleActionServer implements a singe goal policy on top of the ActionServer class.
def get_default_result(self)
def executeLoop(self)
Called from a separate thread to call blocking execute calls.