fibonacci_server.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <actionlib/server/simple_action_server.h>
00003 #include <actionlib_tutorials/FibonacciAction.h>
00004 
00005 class FibonacciAction
00006 {
00007 protected:
00008 
00009   ros::NodeHandle nh_;
00010   actionlib::SimpleActionServer<actionlib_tutorials::FibonacciAction> as_; // NodeHandle instance must be created before this line. Otherwise strange error occurs.
00011   std::string action_name_;
00012   // create messages that are used to published feedback/result
00013   actionlib_tutorials::FibonacciFeedback feedback_;
00014   actionlib_tutorials::FibonacciResult result_;
00015 
00016 public:
00017 
00018   FibonacciAction(std::string name) :
00019     as_(nh_, name, boost::bind(&FibonacciAction::executeCB, this, _1), false),
00020     action_name_(name)
00021   {
00022     as_.start();
00023   }
00024 
00025   ~FibonacciAction(void)
00026   {
00027   }
00028 
00029   void executeCB(const actionlib_tutorials::FibonacciGoalConstPtr &goal)
00030   {
00031     // helper variables
00032     ros::Rate r(1);
00033     bool success = true;
00034 
00035     // push_back the seeds for the fibonacci sequence
00036     feedback_.sequence.clear();
00037     feedback_.sequence.push_back(0);
00038     feedback_.sequence.push_back(1);
00039 
00040     // publish info to the console for the user
00041     ROS_INFO("%s: Executing, creating fibonacci sequence of order %i with seeds %i, %i", action_name_.c_str(), goal->order, feedback_.sequence[0], feedback_.sequence[1]);
00042 
00043     // start executing the action
00044     for(int i=1; i<=goal->order; i++)
00045     {
00046       // check that preempt has not been requested by the client
00047       if (as_.isPreemptRequested() || !ros::ok())
00048       {
00049         ROS_INFO("%s: Preempted", action_name_.c_str());
00050         // set the action state to preempted
00051         as_.setPreempted();
00052         success = false;
00053         break;
00054       }
00055       feedback_.sequence.push_back(feedback_.sequence[i] + feedback_.sequence[i-1]);
00056       // publish the feedback
00057       as_.publishFeedback(feedback_);
00058       // this sleep is not necessary, the sequence is computed at 1 Hz for demonstration purposes
00059       r.sleep();
00060     }
00061 
00062     if(success)
00063     {
00064       result_.sequence = feedback_.sequence;
00065       ROS_INFO("%s: Succeeded", action_name_.c_str());
00066       // set the action state to succeeded
00067       as_.setSucceeded(result_);
00068     }
00069   }
00070 
00071 
00072 };
00073 
00074 
00075 int main(int argc, char** argv)
00076 {
00077   ros::init(argc, argv, "fibonacci");
00078 
00079   FibonacciAction fibonacci("fibonacci");
00080   ros::spin();
00081 
00082   return 0;
00083 }


actionlib_tutorials
Author(s): Melonee Wise
autogenerated on Thu Jun 6 2019 21:11:25