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 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. | |
ActionServer (ros::NodeHandle n, std::string name, boost::function< void(GoalHandle)> goal_cb, bool auto_start) | |
Constructor for an ActionServer. | |
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. | |
ActionServer (ros::NodeHandle n, std::string name, bool auto_start) | |
Constructor for an ActionServer. | |
ROS_DEPRECATED | ActionServer (ros::NodeHandle n, std::string name) |
DEPRECATED Constructor for an ActionServer. | |
virtual | ~ActionServer () |
Destructor for the ActionServer. | |
Private Member Functions | |
virtual void | initialize () |
Initialize all ROS connections and setup timers. | |
virtual void | publishFeedback (const actionlib_msgs::GoalStatus &status, const Feedback &feedback) |
Publishes feedback for a given goal. | |
virtual void | publishResult (const actionlib_msgs::GoalStatus &status, const Result &result) |
Publishes a result for a given goal. | |
virtual void | publishStatus () |
Explicitly publish status. | |
void | publishStatus (const ros::TimerEvent &e) |
Publish status for all goals on a timer event. | |
Private Attributes | |
ros::Subscriber | cancel_sub_ |
ros::Publisher | feedback_pub_ |
ros::Subscriber | goal_sub_ |
ros::NodeHandle | node_ |
ros::Publisher | result_pub_ |
ros::Publisher | status_pub_ |
ros::Timer | status_timer_ |
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 69 of file action_server.h.
typedef ServerGoalHandle<ActionSpec> actionlib::ActionServer< ActionSpec >::GoalHandle |
Reimplemented from actionlib::ActionServerBase< ActionSpec >.
Reimplemented in actionlib::RefServer.
Definition at line 73 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 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 68 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 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 99 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 84 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 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 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 55 of file action_server_imp.h.
actionlib::ActionServer< ActionSpec >::~ActionServer | ( | ) | [virtual] |
Destructor for the ActionServer.
Definition at line 114 of file action_server_imp.h.
actionlib::ActionServer< ActionSpec >::ACTION_DEFINITION | ( | ActionSpec | ) |
Reimplemented from actionlib::ActionServerBase< ActionSpec >.
void actionlib::ActionServer< ActionSpec >::initialize | ( | ) | [private, virtual] |
Initialize all ROS connections and setup timers.
Implements actionlib::ActionServerBase< ActionSpec >.
Definition at line 119 of file action_server_imp.h.
void actionlib::ActionServer< ActionSpec >::publishFeedback | ( | const actionlib_msgs::GoalStatus & | status, |
const Feedback & | feedback | ||
) | [private, virtual] |
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 171 of file action_server_imp.h.
void actionlib::ActionServer< ActionSpec >::publishResult | ( | const actionlib_msgs::GoalStatus & | status, |
const Result & | result | ||
) | [private, virtual] |
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 157 of file action_server_imp.h.
void actionlib::ActionServer< ActionSpec >::publishStatus | ( | ) | [private, virtual] |
Explicitly publish status.
Implements actionlib::ActionServerBase< ActionSpec >.
Definition at line 195 of file action_server_imp.h.
void actionlib::ActionServer< ActionSpec >::publishStatus | ( | const ros::TimerEvent & | e | ) | [private] |
Publish status for all goals on a timer event.
Definition at line 184 of file action_server_imp.h.
ros::Subscriber actionlib::ActionServer< ActionSpec >::cancel_sub_ [private] |
Definition at line 166 of file action_server.h.
ros::Publisher actionlib::ActionServer< ActionSpec >::feedback_pub_ [private] |
Definition at line 167 of file action_server.h.
ros::Subscriber actionlib::ActionServer< ActionSpec >::goal_sub_ [private] |
Definition at line 166 of file action_server.h.
ros::NodeHandle actionlib::ActionServer< ActionSpec >::node_ [private] |
Definition at line 164 of file action_server.h.
ros::Publisher actionlib::ActionServer< ActionSpec >::result_pub_ [private] |
Definition at line 167 of file action_server.h.
ros::Publisher actionlib::ActionServer< ActionSpec >::status_pub_ [private] |
Definition at line 167 of file action_server.h.
ros::Timer actionlib::ActionServer< ActionSpec >::status_timer_ [private] |
Definition at line 169 of file action_server.h.