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 ACTION_LIB_ACTION_SERVER
00038 #define ACTION_LIB_ACTION_SERVER
00039
00040 #include <ros/ros.h>
00041 #include <boost/thread.hpp>
00042 #include <boost/shared_ptr.hpp>
00043 #include <actionlib_msgs/GoalID.h>
00044 #include <actionlib_msgs/GoalStatusArray.h>
00045 #include <actionlib_msgs/GoalStatus.h>
00046 #include <actionlib/enclosure_deleter.h>
00047 #include <actionlib/goal_id_generator.h>
00048 #include <actionlib/action_definition.h>
00049 #include <actionlib/server/status_tracker.h>
00050 #include <actionlib/server/handle_tracker_deleter.h>
00051 #include <actionlib/server/server_goal_handle.h>
00052 #include <actionlib/server/action_server_base.h>
00053 #include <actionlib/destruction_guard.h>
00054
00055 #include <list>
00056
00057 namespace actionlib {
00068 template <class ActionSpec>
00069 class ActionServer : public ActionServerBase<ActionSpec>
00070 {
00071 public:
00072
00073 typedef ServerGoalHandle<ActionSpec> GoalHandle;
00074
00075
00076 ACTION_DEFINITION(ActionSpec);
00077
00086 ActionServer(ros::NodeHandle n, std::string name,
00087 boost::function<void (GoalHandle)> goal_cb,
00088 boost::function<void (GoalHandle)> cancel_cb,
00089 bool auto_start);
00090
00098 ActionServer(ros::NodeHandle n, std::string name,
00099 boost::function<void (GoalHandle)> goal_cb,
00100 bool auto_start);
00101
00109 ROS_DEPRECATED ActionServer(ros::NodeHandle n, std::string name,
00110 boost::function<void (GoalHandle)> goal_cb,
00111 boost::function<void (GoalHandle)> cancel_cb = boost::function<void (GoalHandle)>());
00112
00119 ActionServer(ros::NodeHandle n, std::string name,
00120 bool auto_start);
00121
00127 ROS_DEPRECATED ActionServer(ros::NodeHandle n, std::string name);
00128
00132 virtual ~ActionServer();
00133
00134 private:
00138 virtual void initialize();
00139
00145 virtual void publishResult(const actionlib_msgs::GoalStatus& status, const Result& result);
00146
00152 virtual void publishFeedback(const actionlib_msgs::GoalStatus& status, const Feedback& feedback);
00153
00157 virtual void publishStatus();
00158
00162 void publishStatus(const ros::TimerEvent& e);
00163
00164 ros::NodeHandle node_;
00165
00166 ros::Subscriber goal_sub_, cancel_sub_;
00167 ros::Publisher status_pub_, result_pub_, feedback_pub_;
00168
00169 ros::Timer status_timer_;
00170 };
00171 };
00172
00173
00174 #include <actionlib/server/action_server_imp.h>
00175 #endif