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
00036
00037 #include <actionlib/server/action_server.h>
00038 #include <actionlib/TestAction.h>
00039 #include <ros/ros.h>
00040 #include <cstdio>
00041
00042 namespace actionlib
00043 {
00044
00045 class RefServer : public ActionServer<TestAction>
00046 {
00047 public:
00048 typedef ServerGoalHandle<TestAction> GoalHandle;
00049
00050 RefServer(ros::NodeHandle& n, const std::string& name);
00051
00052 private:
00053
00054 void goalCallback(GoalHandle gh);
00055 void cancelCallback(GoalHandle gh);
00056
00057 };
00058
00059 }
00060
00061 using namespace actionlib;
00062
00063 RefServer::RefServer(ros::NodeHandle& n, const std::string& name)
00064 : ActionServer<TestAction>(n, name,
00065 boost::bind(&RefServer::goalCallback, this, _1),
00066 boost::bind(&RefServer::cancelCallback, this, _1),
00067 false)
00068 {
00069 start();
00070 printf("Creating ActionServer [%s]\n", name.c_str());
00071 }
00072
00073 void RefServer::goalCallback(GoalHandle gh)
00074 {
00075 TestGoal goal = *gh.getGoal();
00076
00077 switch (goal.goal)
00078 {
00079 case 1:
00080 gh.setAccepted();
00081 gh.setSucceeded(TestResult(), "The ref server has succeeded");
00082 break;
00083 case 2:
00084 gh.setAccepted();
00085 gh.setAborted(TestResult(), "The ref server has aborted");
00086 break;
00087 case 3:
00088 gh.setRejected(TestResult(), "The ref server has rejected");
00089 break;
00090 default:
00091 break;
00092 }
00093 }
00094
00095 void RefServer::cancelCallback(GoalHandle gh)
00096 {
00097
00098
00099 }
00100
00101
00102 int main(int argc, char** argv)
00103 {
00104 ros::init(argc, argv, "ref_server");
00105
00106 ros::NodeHandle nh;
00107
00108 RefServer ref_server(nh, "reference_action");
00109
00110 ros::spin();
00111 }
00112
00113