#include <simple_action_server.h>
Public Types | |
typedef boost::function< void(const GoalConstPtr &)> | ExecuteCallback |
typedef ActionServer < ActionSpec >::GoalHandle | GoalHandle |
Public Member Functions | |
boost::shared_ptr< const Goal > | acceptNewGoal () |
Accepts a new goal when one is available The status of this goal is set to active upon acceptance, and the status of any previously active goal is set to preempted. Preempts received for the new goal between checking if isNewGoalAvailable or invokation of a goal callback and the acceptNewGoal call will not trigger a preempt callback. This means, isPreemptReqauested should be called after accepting the goal even for callback-based implementations to make sure the new goal does not have a pending preempt request. | |
ACTION_DEFINITION (ActionSpec) | |
bool | isActive () |
Allows polling implementations to query about the status of the current goal. | |
bool | isNewGoalAvailable () |
Allows polling implementations to query about the availability of a new goal. | |
bool | isPreemptRequested () |
Allows polling implementations to query about preempt requests. | |
void | publishFeedback (const FeedbackConstPtr &feedback) |
Publishes feedback for a given goal. | |
void | publishFeedback (const Feedback &feedback) |
Publishes feedback for a given goal. | |
void | registerGoalCallback (boost::function< void()> cb) |
Allows users to register a callback to be invoked when a new goal is available. | |
void | registerPreemptCallback (boost::function< void()> cb) |
Allows users to register a callback to be invoked when a new preempt request is available. | |
void | setAborted (const Result &result=Result(), const std::string &text=std::string("")) |
Sets the status of the active goal to aborted. | |
void | setPreempted (const Result &result=Result(), const std::string &text=std::string("")) |
Sets the status of the active goal to preempted. | |
void | setSucceeded (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. | |
SimpleActionServer (std::string name, ExecuteCallback execute_cb, bool auto_start) | |
Constructor for a SimpleActionServer. | |
SimpleActionServer (std::string name, bool auto_start) | |
Constructor for a SimpleActionServer. | |
ROS_DEPRECATED | SimpleActionServer (std::string name, ExecuteCallback execute_cb=NULL) |
DEPRECATED: Constructor for a SimpleActionServer. | |
SimpleActionServer (ros::NodeHandle n, std::string name, ExecuteCallback execute_cb, bool auto_start) | |
Constructor for a SimpleActionServer. | |
SimpleActionServer (ros::NodeHandle n, std::string name, bool auto_start) | |
Constructor for a SimpleActionServer. | |
ROS_DEPRECATED | SimpleActionServer (ros::NodeHandle n, std::string name, ExecuteCallback execute_cb=NULL) |
Constructor for a SimpleActionServer. | |
void | start () |
Explicitly start the action server, used it auto_start is set to false. | |
~SimpleActionServer () | |
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 | |
boost::shared_ptr < ActionServer< ActionSpec > > | as_ |
GoalHandle | current_goal_ |
ExecuteCallback | execute_callback_ |
boost::condition | execute_condition_ |
boost::thread * | execute_thread_ |
boost::function< void()> | goal_callback_ |
boost::recursive_mutex | lock_ |
ros::NodeHandle | n_ |
bool | need_to_terminate_ |
bool | new_goal_ |
bool | new_goal_preempt_request_ |
GoalHandle | next_goal_ |
boost::function< void()> | preempt_callback_ |
bool | preempt_request_ |
boost::mutex | terminate_mutex_ |
SimpleActionServer implements a singe goal policy on top of the ActionServer class. The specification of the policy is as follows: only one goal can have an active status at a time, new goals preempt previous goals based on the stamp in their GoalID field (later goals preempt earlier ones), an explicit preempt goal preempts all goals with timestamps that are less than or equal to the stamp associated with the preempt, accepting a new goal implies successful preemption of any old goal and the status of the old goal will be change automatically to reflect this.
Definition at line 57 of file simple_action_server.h.
typedef boost::function<void (const GoalConstPtr&)> actionlib::SimpleActionServer< ActionSpec >::ExecuteCallback |
Definition at line 63 of file simple_action_server.h.
typedef ActionServer<ActionSpec>::GoalHandle actionlib::SimpleActionServer< ActionSpec >::GoalHandle |
Definition at line 62 of file simple_action_server.h.
actionlib::SimpleActionServer< ActionSpec >::SimpleActionServer | ( | std::string | name, |
ExecuteCallback | execute_cb, | ||
bool | auto_start | ||
) |
Constructor for a SimpleActionServer.
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 41 of file simple_action_server_imp.h.
actionlib::SimpleActionServer< ActionSpec >::SimpleActionServer | ( | std::string | name, |
bool | auto_start | ||
) |
Constructor for a SimpleActionServer.
name | A name for the action server |
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 58 of file simple_action_server_imp.h.
actionlib::SimpleActionServer< ActionSpec >::SimpleActionServer | ( | std::string | name, |
ExecuteCallback | execute_cb = NULL |
||
) |
DEPRECATED: Constructor for a SimpleActionServer.
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. |
Definition at line 74 of file simple_action_server_imp.h.
actionlib::SimpleActionServer< ActionSpec >::SimpleActionServer | ( | ros::NodeHandle | n, |
std::string | name, | ||
ExecuteCallback | execute_cb, | ||
bool | auto_start | ||
) |
Constructor for a SimpleActionServer.
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 91 of file simple_action_server_imp.h.
actionlib::SimpleActionServer< ActionSpec >::SimpleActionServer | ( | ros::NodeHandle | n, |
std::string | name, | ||
bool | auto_start | ||
) |
Constructor for a SimpleActionServer.
n | A NodeHandle to create a namespace under |
name | A name for the action server |
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 107 of file simple_action_server_imp.h.
actionlib::SimpleActionServer< ActionSpec >::SimpleActionServer | ( | ros::NodeHandle | n, |
std::string | name, | ||
ExecuteCallback | execute_cb = NULL |
||
) |
Constructor for a SimpleActionServer.
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. |
Definition at line 123 of file simple_action_server_imp.h.
actionlib::SimpleActionServer< ActionSpec >::~SimpleActionServer | ( | ) |
Definition at line 139 of file simple_action_server_imp.h.
boost::shared_ptr< const typename SimpleActionServer< ActionSpec >::Goal > actionlib::SimpleActionServer< ActionSpec >::acceptNewGoal | ( | ) |
Accepts a new goal when one is available The status of this goal is set to active upon acceptance, and the status of any previously active goal is set to preempted. Preempts received for the new goal between checking if isNewGoalAvailable or invokation of a goal callback and the acceptNewGoal call will not trigger a preempt callback. This means, isPreemptReqauested should be called after accepting the goal even for callback-based implementations to make sure the new goal does not have a pending preempt request.
Definition at line 163 of file simple_action_server_imp.h.
actionlib::SimpleActionServer< ActionSpec >::ACTION_DEFINITION | ( | ActionSpec | ) |
void actionlib::SimpleActionServer< ActionSpec >::executeLoop | ( | ) | [private] |
Called from a separate thread to call blocking execute calls.
Definition at line 321 of file simple_action_server_imp.h.
void actionlib::SimpleActionServer< ActionSpec >::goalCallback | ( | GoalHandle | goal | ) | [private] |
Callback for when the ActionServer receives a new goal and passes it on.
Definition at line 261 of file simple_action_server_imp.h.
bool actionlib::SimpleActionServer< ActionSpec >::isActive | ( | ) |
Allows polling implementations to query about the status of the current goal.
Definition at line 206 of file simple_action_server_imp.h.
bool actionlib::SimpleActionServer< ActionSpec >::isNewGoalAvailable | ( | ) |
Allows polling implementations to query about the availability of a new goal.
Definition at line 195 of file simple_action_server_imp.h.
bool actionlib::SimpleActionServer< ActionSpec >::isPreemptRequested | ( | ) |
Allows polling implementations to query about preempt requests.
Definition at line 201 of file simple_action_server_imp.h.
void actionlib::SimpleActionServer< ActionSpec >::preemptCallback | ( | GoalHandle | preempt | ) | [private] |
Callback for when the ActionServer receives a new preempt and passes it on.
Definition at line 300 of file simple_action_server_imp.h.
void actionlib::SimpleActionServer< ActionSpec >::publishFeedback | ( | const FeedbackConstPtr & | feedback | ) |
Publishes feedback for a given goal.
feedback | Shared pointer to the feedback to publish |
Definition at line 249 of file simple_action_server_imp.h.
void actionlib::SimpleActionServer< ActionSpec >::publishFeedback | ( | const Feedback & | feedback | ) |
Publishes feedback for a given goal.
feedback | The feedback to publish |
Definition at line 255 of file simple_action_server_imp.h.
void actionlib::SimpleActionServer< ActionSpec >::registerGoalCallback | ( | boost::function< void()> | cb | ) |
Allows users to register a callback to be invoked when a new goal is available.
cb | The callback to be invoked |
Definition at line 235 of file simple_action_server_imp.h.
void actionlib::SimpleActionServer< ActionSpec >::registerPreemptCallback | ( | boost::function< void()> | cb | ) |
Allows users to register a callback to be invoked when a new preempt request is available.
cb | The callback to be invoked |
Definition at line 244 of file simple_action_server_imp.h.
void actionlib::SimpleActionServer< ActionSpec >::setAborted | ( | 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 221 of file simple_action_server_imp.h.
void actionlib::SimpleActionServer< ActionSpec >::setPreempted | ( | 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 228 of file simple_action_server_imp.h.
void actionlib::SimpleActionServer< ActionSpec >::setSucceeded | ( | 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 214 of file simple_action_server_imp.h.
void actionlib::SimpleActionServer< ActionSpec >::shutdown | ( | ) |
Explicitly shutdown the action server.
Definition at line 146 of file simple_action_server_imp.h.
void actionlib::SimpleActionServer< ActionSpec >::start | ( | ) |
Explicitly start the action server, used it auto_start is set to false.
Definition at line 361 of file simple_action_server_imp.h.
boost::shared_ptr<ActionServer<ActionSpec> > actionlib::SimpleActionServer< ActionSpec >::as_ [private] |
Definition at line 228 of file simple_action_server.h.
GoalHandle actionlib::SimpleActionServer< ActionSpec >::current_goal_ [private] |
Definition at line 230 of file simple_action_server.h.
ExecuteCallback actionlib::SimpleActionServer< ActionSpec >::execute_callback_ [private] |
Definition at line 238 of file simple_action_server.h.
boost::condition actionlib::SimpleActionServer< ActionSpec >::execute_condition_ [private] |
Definition at line 240 of file simple_action_server.h.
boost::thread* actionlib::SimpleActionServer< ActionSpec >::execute_thread_ [private] |
Definition at line 241 of file simple_action_server.h.
boost::function<void ()> actionlib::SimpleActionServer< ActionSpec >::goal_callback_ [private] |
Definition at line 236 of file simple_action_server.h.
boost::recursive_mutex actionlib::SimpleActionServer< ActionSpec >::lock_ [private] |
Definition at line 234 of file simple_action_server.h.
ros::NodeHandle actionlib::SimpleActionServer< ActionSpec >::n_ [private] |
Definition at line 226 of file simple_action_server.h.
bool actionlib::SimpleActionServer< ActionSpec >::need_to_terminate_ [private] |
Definition at line 244 of file simple_action_server.h.
bool actionlib::SimpleActionServer< ActionSpec >::new_goal_ [private] |
Definition at line 232 of file simple_action_server.h.
bool actionlib::SimpleActionServer< ActionSpec >::new_goal_preempt_request_ [private] |
Definition at line 232 of file simple_action_server.h.
GoalHandle actionlib::SimpleActionServer< ActionSpec >::next_goal_ [private] |
Definition at line 230 of file simple_action_server.h.
boost::function<void ()> actionlib::SimpleActionServer< ActionSpec >::preempt_callback_ [private] |
Definition at line 237 of file simple_action_server.h.
bool actionlib::SimpleActionServer< ActionSpec >::preempt_request_ [private] |
Definition at line 232 of file simple_action_server.h.
boost::mutex actionlib::SimpleActionServer< ActionSpec >::terminate_mutex_ [private] |
Definition at line 243 of file simple_action_server.h.