Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef ACTIONLIB__SERVER__ACTION_SERVER_H_
00038 #define ACTIONLIB__SERVER__ACTION_SERVER_H_
00039
00040 #include <ros/ros.h>
00041 #include <boost/thread.hpp>
00042 #include <boost/thread/reverse_lock.hpp>
00043 #include <boost/shared_ptr.hpp>
00044 #include <actionlib_msgs/GoalID.h>
00045 #include <actionlib_msgs/GoalStatusArray.h>
00046 #include <actionlib_msgs/GoalStatus.h>
00047 #include <actionlib/enclosure_deleter.h>
00048 #include <actionlib/goal_id_generator.h>
00049 #include <actionlib/action_definition.h>
00050 #include <actionlib/server/status_tracker.h>
00051 #include <actionlib/server/handle_tracker_deleter.h>
00052 #include <actionlib/server/server_goal_handle.h>
00053 #include <actionlib/server/action_server_base.h>
00054 #include <actionlib/destruction_guard.h>
00055
00056 #include <list>
00057 #include <string>
00058
00059 namespace actionlib
00060 {
00071 template<class ActionSpec>
00072 class ActionServer : public ActionServerBase<ActionSpec>
00073 {
00074 public:
00075
00076 typedef ServerGoalHandle<ActionSpec> GoalHandle;
00077
00078
00079 ACTION_DEFINITION(ActionSpec);
00080
00089 ActionServer(ros::NodeHandle n, std::string name,
00090 boost::function<void(GoalHandle)> goal_cb,
00091 boost::function<void(GoalHandle)> cancel_cb,
00092 bool auto_start);
00093
00101 ActionServer(ros::NodeHandle n, std::string name,
00102 boost::function<void(GoalHandle)> goal_cb,
00103 bool auto_start);
00104
00112 ROS_DEPRECATED ActionServer(ros::NodeHandle n, std::string name,
00113 boost::function<void(GoalHandle)> goal_cb,
00114 boost::function<void(GoalHandle)> cancel_cb = boost::function<void(GoalHandle)>());
00115
00122 ActionServer(ros::NodeHandle n, std::string name,
00123 bool auto_start);
00124
00130 ROS_DEPRECATED ActionServer(ros::NodeHandle n, std::string name);
00131
00135 virtual ~ActionServer();
00136
00137 private:
00141 virtual void initialize();
00142
00148 virtual void publishResult(const actionlib_msgs::GoalStatus & status, const Result & result);
00149
00155 virtual void publishFeedback(const actionlib_msgs::GoalStatus & status,
00156 const Feedback & feedback);
00157
00161 virtual void publishStatus();
00162
00166 void publishStatus(const ros::TimerEvent & e);
00167
00168 ros::NodeHandle node_;
00169
00170 ros::Subscriber goal_sub_, cancel_sub_;
00171 ros::Publisher status_pub_, result_pub_, feedback_pub_;
00172
00173 ros::Timer status_timer_;
00174 };
00175 }
00176
00177
00178 #include <actionlib/server/action_server_imp.h>
00179 #endif // ACTIONLIB__SERVER__ACTION_SERVER_H_