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...
#include <action_server.h>
Public Types | |
typedef ServerGoalHandle< ActionSpec > | GoalHandle |
Public Types inherited from actionlib::ActionServerBase< ActionSpec > | |
typedef ServerGoalHandle< ActionSpec > | GoalHandle |
Public Member Functions | |
ACTION_DEFINITION (ActionSpec) | |
ActionServer (ros::NodeHandle n, std::string name, boost::function< void(GoalHandle)> goal_cb, boost::function< void(GoalHandle)> cancel_cb, bool auto_start) | |
Constructor for an ActionServer. More... | |
ActionServer (ros::NodeHandle n, std::string name, boost::function< void(GoalHandle)> goal_cb, bool auto_start) | |
Constructor for an ActionServer. More... | |
ROS_DEPRECATED | ActionServer (ros::NodeHandle n, std::string name, boost::function< void(GoalHandle)> goal_cb, boost::function< void(GoalHandle)> cancel_cb=boost::function< void(GoalHandle)>()) |
DEPRECATED Constructor for an ActionServer. More... | |
ActionServer (ros::NodeHandle n, std::string name, bool auto_start) | |
Constructor for an ActionServer. More... | |
ROS_DEPRECATED | ActionServer (ros::NodeHandle n, std::string name) |
DEPRECATED Constructor for an ActionServer. More... | |
virtual | ~ActionServer () |
Destructor for the ActionServer. More... | |
Public Member Functions inherited from actionlib::ActionServerBase< ActionSpec > | |
ACTION_DEFINITION (ActionSpec) | |
ActionServerBase (boost::function< void(GoalHandle)> goal_cb, boost::function< void(GoalHandle)> cancel_cb, bool auto_start=false) | |
Constructor for an ActionServer. More... | |
void | cancelCallback (const boost::shared_ptr< const actionlib_msgs::GoalID > &goal_id) |
The ROS callback for cancel requests coming into the ActionServerBase. More... | |
void | goalCallback (const boost::shared_ptr< const ActionGoal > &goal) |
The ROS callback for goals coming into the ActionServerBase. More... | |
void | registerCancelCallback (boost::function< void(GoalHandle)> cb) |
Register a callback to be invoked when a new cancel is received, this will replace any previously registered callback. More... | |
void | registerGoalCallback (boost::function< void(GoalHandle)> cb) |
Register a callback to be invoked when a new goal is received, this will replace any previously registered callback. More... | |
void | start () |
Explicitly start the action server, used it auto_start is set to false. More... | |
virtual | ~ActionServerBase () |
Destructor for the ActionServerBase. More... | |
Private Member Functions | |
virtual void | initialize () |
Initialize all ROS connections and setup timers. More... | |
virtual void | publishFeedback (const actionlib_msgs::GoalStatus &status, const Feedback &feedback) |
Publishes feedback for a given goal. More... | |
virtual void | publishResult (const actionlib_msgs::GoalStatus &status, const Result &result) |
Publishes a result for a given goal. More... | |
virtual void | publishStatus () |
Explicitly publish status. More... | |
void | publishStatus (const ros::TimerEvent &e) |
Publish status for all goals on a timer event. More... | |
Additional Inherited Members | |
Protected Attributes inherited from actionlib::ActionServerBase< ActionSpec > | |
boost::function< void(GoalHandle)> | cancel_callback_ |
boost::function< void(GoalHandle)> | goal_callback_ |
boost::shared_ptr< DestructionGuard > | guard_ |
GoalIDGenerator | id_generator_ |
ros::Time | last_cancel_ |
boost::recursive_mutex | lock_ |
bool | started_ |
std::list< StatusTracker< ActionSpec > > | status_list_ |
ros::Duration | status_list_timeout_ |
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 72 of file action_server.h.
typedef ServerGoalHandle<ActionSpec> actionlib::ActionServer< ActionSpec >::GoalHandle |
Definition at line 76 of file action_server.h.
actionlib::ActionServer< ActionSpec >::ActionServer | ( | ros::NodeHandle | n, |
std::string | name, | ||
boost::function< void(GoalHandle)> | goal_cb, | ||
boost::function< void(GoalHandle)> | cancel_cb, | ||
bool | auto_start | ||
) |
Constructor for an ActionServer.
n | A NodeHandle to create a namespace under |
name | The name 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 80 of file action_server_imp.h.
actionlib::ActionServer< ActionSpec >::ActionServer | ( | ros::NodeHandle | n, |
std::string | name, | ||
boost::function< void(GoalHandle)> | goal_cb, | ||
bool | auto_start | ||
) |
Constructor for an ActionServer.
n | A NodeHandle to create a namespace under |
name | The name of the action |
goal_cb | A goal callback to be called when the ActionServer receives a new goal 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 115 of file action_server_imp.h.
actionlib::ActionServer< ActionSpec >::ActionServer | ( | ros::NodeHandle | n, |
std::string | name, | ||
boost::function< void(GoalHandle)> | goal_cb, | ||
boost::function< void(GoalHandle)> | cancel_cb = boost::function<void(GoalHandle)>() |
||
) |
DEPRECATED Constructor for an ActionServer.
n | A NodeHandle to create a namespace under |
name | The name 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 |
Definition at line 98 of file action_server_imp.h.
actionlib::ActionServer< ActionSpec >::ActionServer | ( | ros::NodeHandle | n, |
std::string | name, | ||
bool | auto_start | ||
) |
Constructor for an ActionServer.
n | A NodeHandle to create a namespace under |
name | The name of the action |
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 47 of file action_server_imp.h.
actionlib::ActionServer< ActionSpec >::ActionServer | ( | ros::NodeHandle | n, |
std::string | name | ||
) |
DEPRECATED Constructor for an ActionServer.
n | A NodeHandle to create a namespace under |
name | The name of the action |
Definition at line 64 of file action_server_imp.h.
|
virtual |
Destructor for the ActionServer.
Definition at line 132 of file action_server_imp.h.
actionlib::ActionServer< ActionSpec >::ACTION_DEFINITION | ( | ActionSpec | ) |
|
privatevirtual |
Initialize all ROS connections and setup timers.
Implements actionlib::ActionServerBase< ActionSpec >.
Definition at line 137 of file action_server_imp.h.
|
privatevirtual |
Publishes feedback for a given goal.
status | The status of the goal with which the feedback is associated |
feedback | The feedback to publish |
Implements actionlib::ActionServerBase< ActionSpec >.
Definition at line 203 of file action_server_imp.h.
|
privatevirtual |
Publishes a result for a given goal.
status | The status of the goal with which the result is associated |
result | The result to publish |
Implements actionlib::ActionServerBase< ActionSpec >.
Definition at line 187 of file action_server_imp.h.
|
privatevirtual |
Explicitly publish status.
Implements actionlib::ActionServerBase< ActionSpec >.
Definition at line 230 of file action_server_imp.h.
|
private |
Publish status for all goals on a timer event.
Definition at line 218 of file action_server_imp.h.
|
private |
Definition at line 170 of file action_server.h.
|
private |
Definition at line 171 of file action_server.h.
|
private |
Definition at line 170 of file action_server.h.
|
private |
Definition at line 168 of file action_server.h.
|
private |
Definition at line 171 of file action_server.h.
|
private |
Definition at line 171 of file action_server.h.
|
private |
Definition at line 173 of file action_server.h.