Go to the documentation of this file.
34 from actionlib_msgs.msg
import GoalStatus
36 from actionlib
import ActionServer
61 def __init__(self, name, ActionSpec, execute_cb=None, auto_start=True):
78 self.
lock = threading.RLock()
114 rospy.logerr(
"Attempting to accept the next goal when a new goal is not available")
119 self.
current_goal.set_canceled(
None,
"This goal was canceled because another goal was received by the simple action server")
121 rospy.logdebug(
"Accepting a new goal")
132 self.
current_goal.set_accepted(
"This goal has been accepted by the simple action server")
153 return status == GoalStatus.ACTIVE
or status == GoalStatus.PREEMPTING
185 rospy.logdebug(
"Setting the current goal as canceled")
192 rospy.logwarn(
"Cannot call SimpleActionServer.register_goal_callback() because an executeCallback exists. Not going to register it.")
210 rospy.logdebug(
"A new goal %s has been received by the single goal action server", goal.get_goal_id().id)
214 and (
not self.
next_goal.get_goal()
or goal.get_goal_id().stamp >= self.
next_goal.get_goal_id().stamp)):
217 self.
next_goal.set_canceled(
None,
"This goal was canceled because another goal was received by the simple action server")
239 goal.set_canceled(
None,
"This goal was canceled because another goal was received by the simple action server")
241 except Exception
as e:
242 rospy.logerr(
"SimpleActionServer.internal_goal_callback - exception %s", str(e))
248 rospy.logdebug(
"A preempt has been received by the SimpleActionServer")
252 rospy.logdebug(
"Setting preempt_request bit for the current goal to TRUE and invoking callback")
260 rospy.logdebug(
"Setting preempt request bit for the next goal to TRUE")
265 loop_duration = rospy.Duration.from_sec(.1)
267 while (
not rospy.is_shutdown()):
277 rospy.logerr(
"Should never reach this code with an active goal")
284 rospy.logerr(
"execute_callback_ must exist. This is a bug in SimpleActionServer")
291 rospy.logwarn(
"Your executeCallback did not set the goal to a terminal status. " +
292 "This is a bug in your ActionServer implementation. Fix your code! " +
293 "For now, the ActionServer will set this goal to aborted")
294 self.
set_aborted(
None,
"No terminal state was set.")
295 except Exception
as ex:
296 rospy.logerr(
"Exception in your execute callback: %s\n%s", str(ex),
297 traceback.format_exc())
298 self.
set_aborted(
None,
"Exception in execute callback: %s" % str(ex))
def register_goal_callback(self, cb)
Allows users to register a callback to be invoked when a new goal is available.
def set_succeeded(self, result=None, text="")
Sets the status of the active goal to succeeded.
The ActionServer is a helpful tool for managing goal requests to a node. It allows the user to specif...
def set_aborted(self, result=None, text="")
Sets the status of the active goal to aborted.
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 __init__(self, name, ActionSpec, execute_cb=None, auto_start=True)
Constructor for a SimpleActionServer.
def start(self)
Explicitly start the action server, used it auto_start is set to false.
def register_preempt_callback(self, cb)
Allows users to register a callback to be invoked when a new preempt request is available.
def get_default_result(self)
def is_active(self)
Allows polling implementations to query about the status of the current goal.
def set_preempted(self, result=None, text="")
Sets the status of the active goal to preempted.
def executeLoop(self)
Called from a separate thread to call blocking execute calls.
def is_preempt_requested(self)
Allows polling implementations to query about preempt requests.
def internal_goal_callback(self, goal)
Callback for when the ActionServer receives a new goal and passes it on.
def publish_feedback(self, feedback)
Publishes feedback for a given goal.
def is_new_goal_available(self)
Allows polling implementations to query about the availability of a new goal.
The SimpleActionServer implements a singe goal policy on top of the ActionServer class....
def internal_preempt_callback(self, preempt)
Callback for when the ActionServer receives a new preempt and passes it on.
actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Fri May 19 2023 02:36:55