#include <MultiGoalActionServer.h>
Classes | |
class | GoalQueue |
class | GoalQueueItem |
Public Types | |
typedef boost::function< void(GoalHandle)> | ExecuteCallback |
typedef ActionServer < ActionSpec >::GoalHandle | GoalHandle |
Public Member Functions | |
ACTION_DEFINITION (ActionSpec) | |
bool | isActive (GoalHandle goal) |
Allows polling implementations to query about the status of the current goal. | |
bool | isPreemptRequested (GoalHandle goal) |
Allows polling implementations to query about preempt requests. | |
MGActionServer (ros::NodeHandle n, std::string name, ExecuteCallback execute_cb, bool auto_start) | |
Constructor for a MGActionServer. | |
void | removePreemptedGoals (std::vector< boost::thread * > &thread_for_delete) |
void | requestPreemption (GoalHandle gh) |
void | setAborted (GoalHandle gh, const Result &result=Result(), const std::string &text=std::string("")) |
Sets the status of the active goal to aborted. | |
void | setPreempted (GoalHandle gh, const Result &result=Result(), const std::string &text=std::string("")) |
Sets the status of the active goal to preempted. | |
void | setSucceeded (GoalHandle gh, const Result &result=Result(), const std::string &text=std::string("")) |
Sets the status of the active goal to succeeded. | |
void | shutdown () |
Explicitly shutdown the action server. | |
void | start () |
Explicitly start the action server, used it auto_start is set to false. | |
~MGActionServer () | |
Private Member Functions | |
void | executeLoop () |
Called from a separate thread to call blocking execute calls. | |
void | goalCallback (GoalHandle goal) |
Callback for when the ActionServer receives a new goal and passes it on. | |
void | preemptCallback (GoalHandle preempt) |
Callback for when the ActionServer receives a new preempt and passes it on. | |
Private Attributes | |
GoalQueue | active_goals |
boost::shared_ptr < ActionServer< ActionSpec > > | as_ |
ExecuteCallback | execute_callback_ |
boost::condition | execute_condition_ |
boost::thread * | execute_thread_ |
boost::recursive_mutex | lock_ |
ros::NodeHandle | n_ |
bool | need_to_terminate_ |
GoalQueue | new_goals |
boost::mutex | terminate_mutex_ |
MGActionServer implements a multi goal policy on top of the ActionServer class. The specification of the policy is as follows: number of goals can have an active status at a time.
Definition at line 60 of file MultiGoalActionServer.h.
typedef boost::function<void (GoalHandle)> actionlib::MGActionServer< ActionSpec >::ExecuteCallback |
Definition at line 66 of file MultiGoalActionServer.h.
typedef ActionServer<ActionSpec>::GoalHandle actionlib::MGActionServer< ActionSpec >::GoalHandle |
Definition at line 65 of file MultiGoalActionServer.h.
actionlib::MGActionServer< ActionSpec >::MGActionServer | ( | ros::NodeHandle | n, |
std::string | name, | ||
ExecuteCallback | execute_cb, | ||
bool | auto_start | ||
) |
Constructor for a MGActionServer.
n | A NodeHandle to create a namespace under |
name | A name for the action server |
execute_cb | Optional callback that gets called in a separate thread whenever a new goal is received, allowing users to have blocking callbacks. Adding an execute callback also deactivates the goalCallback. |
auto_start | A boolean value that tells the ActionServer wheteher 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 215 of file MultiGoalActionServer.h.
actionlib::MGActionServer< ActionSpec >::~MGActionServer | ( | ) |
Definition at line 238 of file MultiGoalActionServer.h.
actionlib::MGActionServer< ActionSpec >::ACTION_DEFINITION | ( | ActionSpec | ) |
void actionlib::MGActionServer< ActionSpec >::executeLoop | ( | ) | [private] |
Called from a separate thread to call blocking execute calls.
Definition at line 368 of file MultiGoalActionServer.h.
void actionlib::MGActionServer< ActionSpec >::goalCallback | ( | GoalHandle | goal | ) | [private] |
Callback for when the ActionServer receives a new goal and passes it on.
Definition at line 313 of file MultiGoalActionServer.h.
bool actionlib::MGActionServer< ActionSpec >::isActive | ( | GoalHandle | goal | ) |
Allows polling implementations to query about the status of the current goal.
Definition at line 279 of file MultiGoalActionServer.h.
bool actionlib::MGActionServer< ActionSpec >::isPreemptRequested | ( | GoalHandle | goal | ) |
Allows polling implementations to query about preempt requests.
Definition at line 271 of file MultiGoalActionServer.h.
void actionlib::MGActionServer< ActionSpec >::preemptCallback | ( | GoalHandle | preempt | ) | [private] |
Callback for when the ActionServer receives a new preempt and passes it on.
Definition at line 322 of file MultiGoalActionServer.h.
void actionlib::MGActionServer< ActionSpec >::removePreemptedGoals | ( | std::vector< boost::thread * > & | thread_for_delete | ) |
Definition at line 343 of file MultiGoalActionServer.h.
void actionlib::MGActionServer< ActionSpec >::requestPreemption | ( | GoalHandle | gh | ) |
Definition at line 262 of file MultiGoalActionServer.h.
void actionlib::MGActionServer< ActionSpec >::setAborted | ( | GoalHandle | gh, |
const Result & | result = Result() , |
||
const std::string & | text = std::string("") |
||
) |
Sets the status of the active goal to aborted.
result | An optional result to send back to any clients of the goal |
result | An optional text message to send back to any clients of the goal |
Definition at line 297 of file MultiGoalActionServer.h.
void actionlib::MGActionServer< ActionSpec >::setPreempted | ( | GoalHandle | gh, |
const Result & | result = Result() , |
||
const std::string & | text = std::string("") |
||
) |
Sets the status of the active goal to preempted.
result | An optional result to send back to any clients of the goal |
result | An optional text message to send back to any clients of the goal |
Definition at line 305 of file MultiGoalActionServer.h.
void actionlib::MGActionServer< ActionSpec >::setSucceeded | ( | GoalHandle | gh, |
const Result & | result = Result() , |
||
const std::string & | text = std::string("") |
||
) |
Sets the status of the active goal to succeeded.
result | An optional result to send back to any clients of the goal |
result | An optional text message to send back to any clients of the goal |
Definition at line 289 of file MultiGoalActionServer.h.
void actionlib::MGActionServer< ActionSpec >::shutdown | ( | ) |
Explicitly shutdown the action server.
Definition at line 245 of file MultiGoalActionServer.h.
void actionlib::MGActionServer< ActionSpec >::start | ( | ) |
Explicitly start the action server, used it auto_start is set to false.
Definition at line 439 of file MultiGoalActionServer.h.
GoalQueue actionlib::MGActionServer< ActionSpec >::active_goals [private] |
Definition at line 193 of file MultiGoalActionServer.h.
boost::shared_ptr<ActionServer<ActionSpec> > actionlib::MGActionServer< ActionSpec >::as_ [private] |
Definition at line 190 of file MultiGoalActionServer.h.
ExecuteCallback actionlib::MGActionServer< ActionSpec >::execute_callback_ [private] |
Definition at line 199 of file MultiGoalActionServer.h.
boost::condition actionlib::MGActionServer< ActionSpec >::execute_condition_ [private] |
Definition at line 201 of file MultiGoalActionServer.h.
boost::thread* actionlib::MGActionServer< ActionSpec >::execute_thread_ [private] |
Definition at line 202 of file MultiGoalActionServer.h.
boost::recursive_mutex actionlib::MGActionServer< ActionSpec >::lock_ [private] |
Definition at line 197 of file MultiGoalActionServer.h.
ros::NodeHandle actionlib::MGActionServer< ActionSpec >::n_ [private] |
Definition at line 188 of file MultiGoalActionServer.h.
bool actionlib::MGActionServer< ActionSpec >::need_to_terminate_ [private] |
Definition at line 205 of file MultiGoalActionServer.h.
GoalQueue actionlib::MGActionServer< ActionSpec >::new_goals [private] |
Definition at line 193 of file MultiGoalActionServer.h.
boost::mutex actionlib::MGActionServer< ActionSpec >::terminate_mutex_ [private] |
Definition at line 204 of file MultiGoalActionServer.h.