Module actionlib.action_server
Action server. This module contains the ActionServer class to provide actions which can be executed by an ActionClient.
The action server is initialized with at least two callbacks. One is the goal callback. It is called on new incoming goals. The callback gets the ServerGoalHandle for this goal and the associated ActionServer instance as arguments. The callback can then accept or reject the goal by calling the appropriate goal handle method. If the callback does call neither of this method acceptance is assumed. The second callback is the spin callback. It is called in each loop for every goal to execute one step of the goal. Note that due to the nature if Lua and the need for a central main loop your spin method must return as soon as possible. For lengthy actions this means that you cannot run a continuous method for your action, as you possibly would with roscpp or rospy! Lua coroutines might be useful to meet this requirement. The spin callback is optional in the case of short-duration actions. In this case you must send the result in the goal callback! Optionally a cancel callback can be given, which is called when a goal is canceled. It could be used for example for safely stopping a goal. After a goal has been canceled the spin function is no longer called for this goal.
Copyright© Tim Niemueller, Carnegie Mellon University, Intel Research Pittsburgh
Release: Released under BSD license
Functions
ActionServer:cancel_all_goals () | Cancel all goals. |
ActionServer:cancel_goals_before (stamp) | Cancel all before the given time |
ActionServer:finalize () | Finalize instance. |
ActionServer:generate_goal_id () | Generate a unique goal ID. |
ActionServer:get_pending_goals () | Get pending goals. |
ActionServer:new (o) | Constructor. |
ActionServer:process_cancel (message) | Process incoming cancel message. |
ActionServer:process_goal (message) | Process incoming goal. |
ActionServer:publish_feedback (goal_handle, feedback, result) | Publish feedback. |
ActionServer:publish_result (goal_handle, result) | Publish result. |
ActionServer:publish_status () | Publish status. |
ActionServer:spin () | Spin the action server. |
ActionServer:spin_goals () | Spin the goals. |
ServerGoalHandle:abort (result, text) | Abort the given goal. |
ServerGoalHandle:accept () | Accept this goal. |
ServerGoalHandle:cancel (result, text, explanatory) | Cancel the goal. |
ServerGoalHandle:finish (result) | Finish this goal successfully. |
ServerGoalHandle:is_active () | Check if goal is active |
ServerGoalHandle:is_canceled () | Check if goal has been canceled |
ServerGoalHandle:is_pending () | Check if goal is pending |
ServerGoalHandle:is_terminal () | Check if goal is in a terminal state |
ServerGoalHandle:new (o, stamp) | Constructor. |
ServerGoalHandle:reject () | Reject this goal. |
ServerGoalHandle:set_state (state, text) | Set the state. |
ServerGoalHandle:state_changed () | Check if the status has changed. |
ServerGoalHandle:update_expiration () | Update the expiration date. |
Functions
- ActionServer:cancel_all_goals ()
- Cancel all goals.
- ActionServer:cancel_goals_before (stamp)
-
Cancel all before the given time
Parameters
- stamp:
- ActionServer:finalize ()
- Finalize instance.
- ActionServer:generate_goal_id ()
-
Generate a unique goal ID.
Return value:
unique goal ID - ActionServer:get_pending_goals ()
-
Get pending goals. This will filter pending goals from all goals and return them in a list. This function is most useful for implementing a polling goal processing.
Return value:
list of pending goal (handles) - ActionServer:new (o)
-
Constructor.
Parameters
- o: Object initializer, must contain the following fields: name namespace for topics type type of action with the string representation of the action name. goal_cb goal callback spin_cb spin callback (optional) cancel_cb cancel callback (optional)
- ActionServer:process_cancel (message)
-
Process incoming cancel message.
Parameters
- message: cancel message
- ActionServer:process_goal (message)
-
Process incoming goal.
Parameters
- message: appropriately typed goal message
- ActionServer:publish_feedback (goal_handle, feedback, result)
-
Publish feedback.
Parameters
- goal_handle: goal handle for which to publish a result
- feedback:
- result: appropriately typed feedback message. Note that this is not the type ending in ActionFeedback (e.g. TestActionFeedback), but the message specified in the action file (e.g. TestFeedback). The surrounding message is generated automatically from information stored in the goal handle.
- ActionServer:publish_result (goal_handle, result)
-
Publish result. It is recommended to use the ServerGoalHandle methods abort(), cancel() or finish() to send the result.
Parameters
- goal_handle: goal handle for which to publish a result
- result: appropriately typed result message. Note that this is not the type ending in ActionResult (e.g. TestActionResult), but the message specified in the action file (e.g. TestResult). The surrounding message is generated automatically from information stored in the goal handle.
- ActionServer:publish_status ()
- Publish status. To be called only internally. This checks all current goals for their status. If a goal expired it is removed, if any goal has changed its state or the status_update_interval has elapsed a GoalStatusArray message is published.
- ActionServer:spin ()
- Spin the action server. Spins goals and publishes status as needed.
- ActionServer:spin_goals ()
- Spin the goals. Calls the spin callback for all active goals.
- ServerGoalHandle:abort (result, text)
-
Abort the given goal.
Parameters
- result:
- text: explanatory text
- ServerGoalHandle:accept ()
- Accept this goal.
- ServerGoalHandle:cancel (result, text, explanatory)
-
Cancel the goal.
Parameters
- result:
- text:
- explanatory: text
- ServerGoalHandle:finish (result)
-
Finish this goal successfully.
Parameters
- result:
- ServerGoalHandle:is_active ()
-
Check if goal is active
Return value:
true if the goal is active, false otherwise - ServerGoalHandle:is_canceled ()
-
Check if goal has been canceled
Return value:
true if the goal has been canceled, false otherwise - ServerGoalHandle:is_pending ()
-
Check if goal is pending
Return value:
true if the goal is pending, false otherwise - ServerGoalHandle:is_terminal ()
-
Check if goal is in a terminal state
Return value:
true if goal is preempted, recalled, aborted, rejected, or succeeded. - ServerGoalHandle:new (o, stamp)
-
Constructor. Do not call this directly. Goal handles are created by the ActionServer.
Parameters
- o: table which is setup as the object instance and which must have at least the following fields: goal_id the goal ID of this handle server the associated ActionServer instance
- stamp: the time stamp when the goal was started
- ServerGoalHandle:reject ()
- Reject this goal.
- ServerGoalHandle:set_state (state, text)
-
Set the state. To be called only by the ActionServer.
Parameters
- state: new staet
- text: explanatory text to set
- ServerGoalHandle:state_changed ()
- Check if the status has changed.
- ServerGoalHandle:update_expiration ()
- Update the expiration date. The expiration date is reset to be now plus the timeout interval.