37 #ifndef ACTIONLIB__SERVER__ACTION_SERVER_H_ 38 #define ACTIONLIB__SERVER__ACTION_SERVER_H_ 41 #include <boost/thread.hpp> 42 #include <boost/thread/reverse_lock.hpp> 43 #include <boost/shared_ptr.hpp> 44 #include <actionlib_msgs/GoalID.h> 45 #include <actionlib_msgs/GoalStatusArray.h> 46 #include <actionlib_msgs/GoalStatus.h> 71 template<
class ActionSpec>
90 boost::function<
void(GoalHandle)> goal_cb,
91 boost::function<
void(GoalHandle)> cancel_cb,
102 boost::function<
void(GoalHandle)> goal_cb,
113 boost::function<
void(GoalHandle)> goal_cb,
114 boost::function<
void(GoalHandle)> cancel_cb = boost::function<
void(GoalHandle)>());
148 virtual void publishResult(
const actionlib_msgs::GoalStatus & status,
const Result & result);
155 virtual void publishFeedback(
const actionlib_msgs::GoalStatus & status,
156 const Feedback & feedback);
179 #endif // ACTIONLIB__SERVER__ACTION_SERVER_H_
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.
virtual ~ActionServer()
Destructor for the ActionServer.
ros::Subscriber goal_sub_
ServerGoalHandle< ActionSpec > GoalHandle
ros::Publisher status_pub_
virtual void initialize()
Initialize all ROS connections and setup timers.
ros::Publisher feedback_pub_
The ActionServerBase implements the logic for an ActionServer.
virtual void publishResult(const actionlib_msgs::GoalStatus &status, const Result &result)
Publishes a result for a given goal.
Encapsulates a state machine for a given goal that the user can trigger transitions on...
virtual void publishStatus()
Explicitly publish status.
The ActionServer is a helpful tool for managing goal requests to a node. It allows the user to specif...
ros::Subscriber cancel_sub_
ros::Publisher result_pub_
virtual void publishFeedback(const actionlib_msgs::GoalStatus &status, const Feedback &feedback)
Publishes feedback for a given goal.
ACTION_DEFINITION(ActionSpec)