The ActionServer is a helpful tool for managing goal requests to a node. It allows the user to specify callbacks that are invoked when goal or cancel requests come over the wire, and passes back GoalHandles that can be used to track the state of a given goal request. The ActionServer makes no assumptions about the policy used to service these goals, and sends status for each goal over the wire until the last GoalHandle associated with a goal request is destroyed. More...
Public Member Functions | |
def | __init__ (self, ns, ActionSpec, goal_cb, cancel_cb=nop_cb, auto_start=True) |
Constructor for an ActionServer. More... | |
def | initialize (self) |
Initialize all ROS connections and setup timers. More... | |
def | internal_cancel_callback (self, goal_id) |
The ROS callback for cancel requests coming into the ActionServer. More... | |
def | internal_goal_callback (self, goal) |
The ROS callback for goals coming into the ActionServer. More... | |
def | publish_feedback (self, status, feedback) |
Publishes feedback for a given goal. More... | |
def | publish_result (self, status, result) |
Publishes a result for a given goal. More... | |
def | publish_status (self) |
Explicitly publish status. More... | |
def | publish_status_async (self, event) |
Publish status for all goals on a timer event. More... | |
def | register_cancel_callback (self, cancel_cb) |
Register a callback to be invoked when a new cancel is received, this will replace any previously registered callback. More... | |
def | register_goal_callback (self, cb) |
Register a callback to be invoked when a new goal is received, this will replace any previously registered callback. More... | |
def | start (self) |
Start the action server. More... | |
def | stop (self) |
Stop the action server. More... | |
The ActionServer is a helpful tool for managing goal requests to a node. It allows the user to specify callbacks that are invoked when goal or cancel requests come over the wire, and passes back GoalHandles that can be used to track the state of a given goal request. The ActionServer makes no assumptions about the policy used to service these goals, and sends status for each goal over the wire until the last GoalHandle associated with a goal request is destroyed.
Definition at line 56 of file action_server.py.
def actionlib.action_server.ActionServer.__init__ | ( | self, | |
ns, | |||
ActionSpec, | |||
goal_cb, | |||
cancel_cb = nop_cb , |
|||
auto_start = True |
|||
) |
Constructor for an ActionServer.
ns/name | A namespace for the action server |
actionspec | An explicit specification of the action |
goal_cb | A goal callback to be called when the ActionServer receives a new goal over the wire |
cancel_cb | A cancel callback to be called when the ActionServer receives a new cancel request over the wire |
auto_start | A boolean value that tells the ActionServer whether or not to start publishing as soon as it comes up. THIS SHOULD ALWAYS BE SET TO FALSE TO AVOID RACE CONDITIONS and start() should be called after construction of the server. |
Definition at line 63 of file action_server.py.
def actionlib.action_server.ActionServer.initialize | ( | self | ) |
Initialize all ROS connections and setup timers.
Definition at line 136 of file action_server.py.
def actionlib.action_server.ActionServer.internal_cancel_callback | ( | self, | |
goal_id | |||
) |
The ROS callback for cancel requests coming into the ActionServer.
Definition at line 197 of file action_server.py.
def actionlib.action_server.ActionServer.internal_goal_callback | ( | self, | |
goal | |||
) |
The ROS callback for goals coming into the ActionServer.
Definition at line 251 of file action_server.py.
def actionlib.action_server.ActionServer.publish_feedback | ( | self, | |
status, | |||
feedback | |||
) |
Publishes feedback for a given goal.
status | The status of the goal with which the feedback is associated |
feedback | The feedback to publish |
Definition at line 187 of file action_server.py.
def actionlib.action_server.ActionServer.publish_result | ( | self, | |
status, | |||
result | |||
) |
Publishes a result for a given goal.
status | The status of the goal with which the result is associated |
result | The result to publish |
Definition at line 174 of file action_server.py.
def actionlib.action_server.ActionServer.publish_status | ( | self | ) |
Explicitly publish status.
Definition at line 303 of file action_server.py.
def actionlib.action_server.ActionServer.publish_status_async | ( | self, | |
event | |||
) |
Publish status for all goals on a timer event.
Definition at line 295 of file action_server.py.
def actionlib.action_server.ActionServer.register_cancel_callback | ( | self, | |
cancel_cb | |||
) |
Register a callback to be invoked when a new cancel is received, this will replace any previously registered callback.
cb | The callback to invoke |
Definition at line 114 of file action_server.py.
def actionlib.action_server.ActionServer.register_goal_callback | ( | self, | |
cb | |||
) |
Register a callback to be invoked when a new goal is received, this will replace any previously registered callback.
cb | The callback to invoke |
Definition at line 109 of file action_server.py.
def actionlib.action_server.ActionServer.start | ( | self | ) |
Start the action server.
Definition at line 118 of file action_server.py.
def actionlib.action_server.ActionServer.stop | ( | self | ) |
Stop the action server.
Please make sure it is not processing any goals at stop-time.
Definition at line 125 of file action_server.py.
actionlib.action_server.ActionServer.ActionFeedback |
Definition at line 73 of file action_server.py.
actionlib.action_server.ActionServer.ActionGoal |
Definition at line 70 of file action_server.py.
actionlib.action_server.ActionServer.ActionResult |
Definition at line 71 of file action_server.py.
actionlib.action_server.ActionServer.ActionResultType |
Definition at line 72 of file action_server.py.
actionlib.action_server.ActionServer.ActionSpec |
Definition at line 69 of file action_server.py.
actionlib.action_server.ActionServer.auto_start |
Definition at line 98 of file action_server.py.
actionlib.action_server.ActionServer.cancel_callback |
Definition at line 97 of file action_server.py.
actionlib.action_server.ActionServer.cancel_sub |
Definition at line 78 of file action_server.py.
actionlib.action_server.ActionServer.feedback_pub |
Definition at line 81 of file action_server.py.
actionlib.action_server.ActionServer.goal_callback |
Definition at line 94 of file action_server.py.
actionlib.action_server.ActionServer.goal_sub |
Definition at line 77 of file action_server.py.
actionlib.action_server.ActionServer.id_generator |
Definition at line 92 of file action_server.py.
actionlib.action_server.ActionServer.last_cancel |
Definition at line 89 of file action_server.py.
actionlib.action_server.ActionServer.lock |
Definition at line 83 of file action_server.py.
actionlib.action_server.ActionServer.ns |
Definition at line 64 of file action_server.py.
actionlib.action_server.ActionServer.pub_queue_size |
Definition at line 137 of file action_server.py.
actionlib.action_server.ActionServer.result_pub |
Definition at line 80 of file action_server.py.
actionlib.action_server.ActionServer.started |
Definition at line 100 of file action_server.py.
actionlib.action_server.ActionServer.status_frequency |
Definition at line 155 of file action_server.py.
actionlib.action_server.ActionServer.status_list |
Definition at line 87 of file action_server.py.
actionlib.action_server.ActionServer.status_list_timeout |
Definition at line 90 of file action_server.py.
actionlib.action_server.ActionServer.status_pub |
Definition at line 79 of file action_server.py.
actionlib.action_server.ActionServer.status_timer |
Definition at line 85 of file action_server.py.
actionlib.action_server.ActionServer.sub_queue_size |
Definition at line 144 of file action_server.py.