Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
actionlib::SimpleActionServer< ActionSpec > Class Template Reference

#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 invocation of a goal callback and the acceptNewGoal call will not trigger a preempt callback. This means, isPreemptRequested 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. More...
 
bool isActive ()
 Allows polling implementations to query about the status of the current goal. More...
 
bool isNewGoalAvailable ()
 Allows polling implementations to query about the availability of a new goal. More...
 
bool isPreemptRequested ()
 Allows polling implementations to query about preempt requests. More...
 
void publishFeedback (const Feedback &feedback)
 Publishes feedback for a given goal. More...
 
void publishFeedback (const FeedbackConstPtr &feedback)
 Publishes feedback for a given goal. More...
 
void registerGoalCallback (boost::function< void()> cb)
 Allows users to register a callback to be invoked when a new goal is available. More...
 
void registerPreemptCallback (boost::function< void()> cb)
 Allows users to register a callback to be invoked when a new preempt request is available. More...
 
void setAborted (const Result &result=Result(), const std::string &text=std::string(""))
 Sets the status of the active goal to aborted. More...
 
void setPreempted (const Result &result=Result(), const std::string &text=std::string(""))
 Sets the status of the active goal to preempted. More...
 
void setSucceeded (const Result &result=Result(), const std::string &text=std::string(""))
 Sets the status of the active goal to succeeded. More...
 
void shutdown ()
 Explicitly shutdown the action server. More...
 
 SimpleActionServer (ros::NodeHandle n, std::string name, bool auto_start)
 Constructor for a SimpleActionServer. More...
 
 SimpleActionServer (ros::NodeHandle n, std::string name, ExecuteCallback execute_callback, bool auto_start)
 Constructor for a SimpleActionServer. More...
 
ROS_DEPRECATED SimpleActionServer (ros::NodeHandle n, std::string name, ExecuteCallback execute_callback=NULL)
 Constructor for a SimpleActionServer. More...
 
 SimpleActionServer (std::string name, bool auto_start)
 Constructor for a SimpleActionServer. More...
 
 SimpleActionServer (std::string name, ExecuteCallback execute_callback, bool auto_start)
 Constructor for a SimpleActionServer. More...
 
ROS_DEPRECATED SimpleActionServer (std::string name, ExecuteCallback execute_callback=NULL)
 DEPRECATED: Constructor for a SimpleActionServer. More...
 
void start ()
 Explicitly start the action server, used it auto_start is set to false. More...
 
 ~SimpleActionServer ()
 

Private Member Functions

void executeLoop ()
 Called from a separate thread to call blocking execute calls. More...
 
void goalCallback (GoalHandle goal)
 Callback for when the ActionServer receives a new goal and passes it on. More...
 
void preemptCallback (GoalHandle preempt)
 Callback for when the ActionServer receives a new preempt and passes it on. More...
 

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_
 

Detailed Description

template<class ActionSpec>
class actionlib::SimpleActionServer< ActionSpec >

SimpleActionServer implements a single 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 changed automatically to reflect this.

Definition at line 95 of file simple_action_server.h.

Member Typedef Documentation

◆ ExecuteCallback

template<class ActionSpec >
typedef boost::function<void (const GoalConstPtr &)> actionlib::SimpleActionServer< ActionSpec >::ExecuteCallback

Definition at line 102 of file simple_action_server.h.

◆ GoalHandle

template<class ActionSpec >
typedef ActionServer<ActionSpec>::GoalHandle actionlib::SimpleActionServer< ActionSpec >::GoalHandle

Definition at line 101 of file simple_action_server.h.

Constructor & Destructor Documentation

◆ SimpleActionServer() [1/6]

template<class ActionSpec >
actionlib::SimpleActionServer< ActionSpec >::SimpleActionServer ( std::string  name,
ExecuteCallback  execute_callback,
bool  auto_start 
)

Constructor for a SimpleActionServer.

Parameters
nameA name for the action server
execute_callbackOptional 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_startA 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 82 of file simple_action_server_imp.h.

◆ SimpleActionServer() [2/6]

template<class ActionSpec >
actionlib::SimpleActionServer< ActionSpec >::SimpleActionServer ( std::string  name,
bool  auto_start 
)

Constructor for a SimpleActionServer.

Parameters
nameA name for the action server
auto_startA 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 100 of file simple_action_server_imp.h.

◆ SimpleActionServer() [3/6]

template<class ActionSpec >
actionlib::SimpleActionServer< ActionSpec >::SimpleActionServer ( std::string  name,
ExecuteCallback  execute_callback = NULL 
)

DEPRECATED: Constructor for a SimpleActionServer.

Parameters
nameA name for the action server
execute_callbackOptional 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 116 of file simple_action_server_imp.h.

◆ SimpleActionServer() [4/6]

template<class ActionSpec >
actionlib::SimpleActionServer< ActionSpec >::SimpleActionServer ( ros::NodeHandle  n,
std::string  name,
ExecuteCallback  execute_callback,
bool  auto_start 
)

Constructor for a SimpleActionServer.

Parameters
nA NodeHandle to create a namespace under
nameA name for the action server
execute_callbackOptional 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_startA 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 134 of file simple_action_server_imp.h.

◆ SimpleActionServer() [5/6]

template<class ActionSpec >
actionlib::SimpleActionServer< ActionSpec >::SimpleActionServer ( ros::NodeHandle  n,
std::string  name,
bool  auto_start 
)

Constructor for a SimpleActionServer.

Parameters
nA NodeHandle to create a namespace under
nameA name for the action server
auto_startA 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 152 of file simple_action_server_imp.h.

◆ SimpleActionServer() [6/6]

template<class ActionSpec >
actionlib::SimpleActionServer< ActionSpec >::SimpleActionServer ( ros::NodeHandle  n,
std::string  name,
ExecuteCallback  execute_callback = NULL 
)

Constructor for a SimpleActionServer.

Parameters
nA NodeHandle to create a namespace under
nameA name for the action server
execute_callbackOptional 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 169 of file simple_action_server_imp.h.

◆ ~SimpleActionServer()

template<class ActionSpec >
actionlib::SimpleActionServer< ActionSpec >::~SimpleActionServer

Definition at line 186 of file simple_action_server_imp.h.

Member Function Documentation

◆ acceptNewGoal()

template<class ActionSpec >
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 invocation of a goal callback and the acceptNewGoal call will not trigger a preempt callback. This means, isPreemptRequested 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.

Returns
A shared_ptr to the new goal.

Definition at line 213 of file simple_action_server_imp.h.

◆ executeLoop()

template<class ActionSpec >
void actionlib::SimpleActionServer< ActionSpec >::executeLoop
private

Called from a separate thread to call blocking execute calls.

Definition at line 396 of file simple_action_server_imp.h.

◆ goalCallback()

template<class ActionSpec >
void actionlib::SimpleActionServer< ActionSpec >::goalCallback ( GoalHandle  goal)
private

Callback for when the ActionServer receives a new goal and passes it on.

Definition at line 328 of file simple_action_server_imp.h.

◆ isActive()

template<class ActionSpec >
bool actionlib::SimpleActionServer< ActionSpec >::isActive

Allows polling implementations to query about the status of the current goal.

Returns
True if a goal is active, false otherwise

Definition at line 263 of file simple_action_server_imp.h.

◆ isNewGoalAvailable()

template<class ActionSpec >
bool actionlib::SimpleActionServer< ActionSpec >::isNewGoalAvailable

Allows polling implementations to query about the availability of a new goal.

Returns
True if a new goal is available, false otherwise

Definition at line 250 of file simple_action_server_imp.h.

◆ isPreemptRequested()

template<class ActionSpec >
bool actionlib::SimpleActionServer< ActionSpec >::isPreemptRequested

Allows polling implementations to query about preempt requests.

Returns
True if a preempt is requested, false otherwise

Definition at line 257 of file simple_action_server_imp.h.

◆ preemptCallback()

template<class ActionSpec >
void actionlib::SimpleActionServer< ActionSpec >::preemptCallback ( GoalHandle  preempt)
private

Callback for when the ActionServer receives a new preempt and passes it on.

Definition at line 373 of file simple_action_server_imp.h.

◆ publishFeedback() [1/2]

template<class ActionSpec >
void actionlib::SimpleActionServer< ActionSpec >::publishFeedback ( const Feedback &  feedback)

Publishes feedback for a given goal.

Parameters
feedbackThe feedback to publish

Definition at line 322 of file simple_action_server_imp.h.

◆ publishFeedback() [2/2]

template<class ActionSpec >
void actionlib::SimpleActionServer< ActionSpec >::publishFeedback ( const FeedbackConstPtr &  feedback)

Publishes feedback for a given goal.

Parameters
feedbackShared pointer to the feedback to publish

Definition at line 316 of file simple_action_server_imp.h.

◆ registerGoalCallback()

template<class ActionSpec >
void actionlib::SimpleActionServer< ActionSpec >::registerGoalCallback ( boost::function< void()>  cb)

Allows users to register a callback to be invoked when a new goal is available.

Parameters
cbThe callback to be invoked

Definition at line 298 of file simple_action_server_imp.h.

◆ registerPreemptCallback()

template<class ActionSpec >
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.

Parameters
cbThe callback to be invoked

Definition at line 310 of file simple_action_server_imp.h.

◆ setAborted()

template<class ActionSpec >
void actionlib::SimpleActionServer< ActionSpec >::setAborted ( const Result &  result = Result(),
const std::string &  text = std::string("") 
)

Sets the status of the active goal to aborted.

Parameters
resultAn optional result to send back to any clients of the goal
resultAn optional text message to send back to any clients of the goal

Definition at line 282 of file simple_action_server_imp.h.

◆ setPreempted()

template<class ActionSpec >
void actionlib::SimpleActionServer< ActionSpec >::setPreempted ( const Result &  result = Result(),
const std::string &  text = std::string("") 
)

Sets the status of the active goal to preempted.

Parameters
resultAn optional result to send back to any clients of the goal
resultAn optional text message to send back to any clients of the goal

Definition at line 290 of file simple_action_server_imp.h.

◆ setSucceeded()

template<class ActionSpec >
void actionlib::SimpleActionServer< ActionSpec >::setSucceeded ( const Result &  result = Result(),
const std::string &  text = std::string("") 
)

Sets the status of the active goal to succeeded.

Parameters
resultAn optional result to send back to any clients of the goal
resultAn optional text message to send back to any clients of the goal

Definition at line 274 of file simple_action_server_imp.h.

◆ shutdown()

template<class ActionSpec >
void actionlib::SimpleActionServer< ActionSpec >::shutdown

Explicitly shutdown the action server.

Definition at line 194 of file simple_action_server_imp.h.

◆ start()

template<class ActionSpec >
void actionlib::SimpleActionServer< ActionSpec >::start

Explicitly start the action server, used it auto_start is set to false.

Definition at line 439 of file simple_action_server_imp.h.

Member Data Documentation

◆ as_

template<class ActionSpec >
boost::shared_ptr<ActionServer<ActionSpec> > actionlib::SimpleActionServer< ActionSpec >::as_
private

Definition at line 269 of file simple_action_server.h.

◆ current_goal_

template<class ActionSpec >
GoalHandle actionlib::SimpleActionServer< ActionSpec >::current_goal_
private

Definition at line 271 of file simple_action_server.h.

◆ execute_callback_

template<class ActionSpec >
ExecuteCallback actionlib::SimpleActionServer< ActionSpec >::execute_callback_
private

Definition at line 279 of file simple_action_server.h.

◆ execute_condition_

template<class ActionSpec >
boost::condition actionlib::SimpleActionServer< ActionSpec >::execute_condition_
private

Definition at line 281 of file simple_action_server.h.

◆ execute_thread_

template<class ActionSpec >
boost::thread* actionlib::SimpleActionServer< ActionSpec >::execute_thread_
private

Definition at line 282 of file simple_action_server.h.

◆ goal_callback_

template<class ActionSpec >
boost::function<void()> actionlib::SimpleActionServer< ActionSpec >::goal_callback_
private

Definition at line 277 of file simple_action_server.h.

◆ lock_

template<class ActionSpec >
boost::recursive_mutex actionlib::SimpleActionServer< ActionSpec >::lock_
private

Definition at line 275 of file simple_action_server.h.

◆ n_

template<class ActionSpec >
ros::NodeHandle actionlib::SimpleActionServer< ActionSpec >::n_
private

Definition at line 267 of file simple_action_server.h.

◆ need_to_terminate_

template<class ActionSpec >
bool actionlib::SimpleActionServer< ActionSpec >::need_to_terminate_
private

Definition at line 285 of file simple_action_server.h.

◆ new_goal_

template<class ActionSpec >
bool actionlib::SimpleActionServer< ActionSpec >::new_goal_
private

Definition at line 273 of file simple_action_server.h.

◆ new_goal_preempt_request_

template<class ActionSpec >
bool actionlib::SimpleActionServer< ActionSpec >::new_goal_preempt_request_
private

Definition at line 273 of file simple_action_server.h.

◆ next_goal_

template<class ActionSpec >
GoalHandle actionlib::SimpleActionServer< ActionSpec >::next_goal_
private

Definition at line 271 of file simple_action_server.h.

◆ preempt_callback_

template<class ActionSpec >
boost::function<void()> actionlib::SimpleActionServer< ActionSpec >::preempt_callback_
private

Definition at line 278 of file simple_action_server.h.

◆ preempt_request_

template<class ActionSpec >
bool actionlib::SimpleActionServer< ActionSpec >::preempt_request_
private

Definition at line 273 of file simple_action_server.h.

◆ terminate_mutex_

template<class ActionSpec >
boost::mutex actionlib::SimpleActionServer< ActionSpec >::terminate_mutex_
private

Definition at line 284 of file simple_action_server.h.


The documentation for this class was generated from the following files:


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Fri May 19 2023 02:36:55