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/destruction_guard.h>
00053
00054 #include <list>
00055
00056 namespace actionlib {
00067 template <class ActionSpec>
00068 class ActionServer {
00069 public:
00070
00071 typedef ServerGoalHandle<ActionSpec> GoalHandle;
00072
00073
00074 ACTION_DEFINITION(ActionSpec);
00075
00084 ActionServer(ros::NodeHandle n, std::string name,
00085 boost::function<void (GoalHandle)> goal_cb,
00086 boost::function<void (GoalHandle)> cancel_cb,
00087 bool auto_start);
00088
00096 ActionServer(ros::NodeHandle n, std::string name,
00097 boost::function<void (GoalHandle)> goal_cb,
00098 bool auto_start);
00099
00107 ROS_DEPRECATED ActionServer(ros::NodeHandle n, std::string name,
00108 boost::function<void (GoalHandle)> goal_cb,
00109 boost::function<void (GoalHandle)> cancel_cb = boost::function<void (GoalHandle)>());
00110
00117 ActionServer(ros::NodeHandle n, std::string name,
00118 bool auto_start);
00119
00125 ROS_DEPRECATED ActionServer(ros::NodeHandle n, std::string name);
00126
00130 ~ActionServer();
00131
00136 void registerGoalCallback(boost::function<void (GoalHandle)> cb);
00137
00142 void registerCancelCallback(boost::function<void (GoalHandle)> cb);
00143
00147 void start();
00148
00149 private:
00153 void initialize();
00154
00160 void publishResult(const actionlib_msgs::GoalStatus& status, const Result& result);
00161
00167 void publishFeedback(const actionlib_msgs::GoalStatus& status, const Feedback& feedback);
00168
00172 void cancelCallback(const boost::shared_ptr<const actionlib_msgs::GoalID>& goal_id);
00173
00177 void goalCallback(const boost::shared_ptr<const ActionGoal>& goal);
00178
00182 void publishStatus(const ros::TimerEvent& e);
00183
00187 void publishStatus();
00188
00189 ros::NodeHandle node_;
00190
00191 ros::Subscriber goal_sub_, cancel_sub_;
00192 ros::Publisher status_pub_, result_pub_, feedback_pub_;
00193
00194 boost::recursive_mutex lock_;
00195
00196 ros::Timer status_timer_;
00197
00198 std::list<StatusTracker<ActionSpec> > status_list_;
00199
00200 boost::function<void (GoalHandle)> goal_callback_;
00201 boost::function<void (GoalHandle)> cancel_callback_;
00202
00203 ros::Time last_cancel_;
00204 ros::Duration status_list_timeout_;
00205
00206
00207 friend class ServerGoalHandle<ActionSpec>;
00208 friend class HandleTrackerDeleter<ActionSpec>;
00209
00210 GoalIDGenerator id_generator_;
00211 bool started_;
00212 boost::shared_ptr<DestructionGuard> guard_;
00213 };
00214 };
00215
00216
00217 #include <actionlib/server/action_server_imp.h>
00218 #endif