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__SIMPLE_ACTION_SERVER_H_
00038 #define ACTIONLIB__SERVER__SIMPLE_ACTION_SERVER_H_
00039
00040 #include <boost/thread/condition.hpp>
00041 #include <ros/ros.h>
00042 #include <actionlib/server/action_server.h>
00043 #include <actionlib/action_definition.h>
00044
00045 #include <string>
00046
00047 namespace actionlib
00048 {
00059 template<class ActionSpec>
00060 class SimpleActionServer
00061 {
00062 public:
00063
00064 ACTION_DEFINITION(ActionSpec);
00065
00066 typedef typename ActionServer<ActionSpec>::GoalHandle GoalHandle;
00067 typedef boost::function<void (const GoalConstPtr &)> ExecuteCallback;
00068
00077 SimpleActionServer(std::string name, ExecuteCallback execute_callback, bool auto_start);
00078
00084 SimpleActionServer(std::string name, bool auto_start);
00085
00093 ROS_DEPRECATED SimpleActionServer(std::string name, ExecuteCallback execute_callback = NULL);
00094
00104 SimpleActionServer(ros::NodeHandle n, std::string name, ExecuteCallback execute_callback,
00105 bool auto_start);
00106
00113 SimpleActionServer(ros::NodeHandle n, std::string name, bool auto_start);
00114
00123 ROS_DEPRECATED SimpleActionServer(ros::NodeHandle n, std::string name,
00124 ExecuteCallback execute_callback = NULL);
00125
00126 ~SimpleActionServer();
00127
00139 boost::shared_ptr<const Goal> acceptNewGoal();
00140
00145 bool isNewGoalAvailable();
00146
00147
00152 bool isPreemptRequested();
00153
00158 bool isActive();
00159
00165 void setSucceeded(const Result & result = Result(), const std::string & text = std::string(""));
00166
00172 void setAborted(const Result & result = Result(), const std::string & text = std::string(""));
00173
00174
00179 void publishFeedback(const FeedbackConstPtr & feedback);
00180
00185 void publishFeedback(const Feedback & feedback);
00186
00192 void setPreempted(const Result & result = Result(), const std::string & text = std::string(""));
00193
00198 void registerGoalCallback(boost::function<void()> cb);
00199
00204 void registerPreemptCallback(boost::function<void()> cb);
00205
00209 void start();
00210
00214 void shutdown();
00215
00216 private:
00220 void goalCallback(GoalHandle goal);
00221
00225 void preemptCallback(GoalHandle preempt);
00226
00230 void executeLoop();
00231
00232 ros::NodeHandle n_;
00233
00234 boost::shared_ptr<ActionServer<ActionSpec> > as_;
00235
00236 GoalHandle current_goal_, next_goal_;
00237
00238 bool new_goal_, preempt_request_, new_goal_preempt_request_;
00239
00240 boost::recursive_mutex lock_;
00241
00242 boost::function<void()> goal_callback_;
00243 boost::function<void()> preempt_callback_;
00244 ExecuteCallback execute_callback_;
00245
00246 boost::condition execute_condition_;
00247 boost::thread * execute_thread_;
00248
00249 boost::mutex terminate_mutex_;
00250 bool need_to_terminate_;
00251 };
00252
00253 }
00254
00255
00256 #include <actionlib/server/simple_action_server_imp.h>
00257 #endif // ACTIONLIB__SERVER__SIMPLE_ACTION_SERVER_H_