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 #include <sstream>
00037
00038 #include <ros/ros.h>
00039 #include <actionlib/server/simple_action_server.h>
00040 #include <actionlib_tutorials/FibonacciAction.h>
00041
00042 class FibonacciAction
00043 {
00044 public:
00045
00046 FibonacciAction(std::string name) :
00047 as_(nh_, name, boost::bind(&FibonacciAction::executeCB, this, _1)),
00048 action_name_(name)
00049 {
00050
00051 std::stringstream ss;
00052
00053 if(!nh_.getParam(action_name_ + "/seed0", seed0_))
00054 {
00055
00056 ss << action_name_.c_str() << ": Aborted, seed0 param was not set.";
00057 throw ss.str();
00058 }
00059
00060 if(!nh_.getParam(action_name_ + "/seed1", seed1_))
00061 {
00062 ss << action_name_.c_str() << ": Aborted, seed1 param was not set.";
00063 throw ss.str();
00064 }
00065 }
00066
00067 ~FibonacciAction(void)
00068 {
00069 }
00070
00071 void executeCB(const actionlib_tutorials::FibonacciGoalConstPtr &goal)
00072 {
00073
00074 actionlib_tutorials::FibonacciFeedback feedback;
00075 actionlib_tutorials::FibonacciResult result;
00076
00077
00078 ros::Rate r(50);
00079 std::vector<int> sequence;
00080 int temp;
00081 bool success = true;
00082
00083
00084 sequence.push_back(seed0_);
00085 sequence.push_back(seed1_);
00086
00087
00088 ROS_INFO("%s: Executing, creating fibonacci sequence of order %i with seeds %i, %i", action_name_.c_str(), goal->order, sequence[0], sequence[1]);
00089
00090
00091 for(int i=1; i<=goal->order; i++)
00092 {
00093
00094 if (as_.isPreemptRequested() || !ros::ok())
00095 {
00096 ROS_INFO("%s: Preempted", action_name_.c_str());
00097
00098 as_.setPreempted();
00099 success = false;
00100 break;
00101 }
00102 temp = sequence[i] + sequence[i-1];
00103 sequence.push_back(temp);
00104 feedback.set_sequence_vec(sequence);
00105
00106 as_.publishFeedback(feedback);
00107
00108 r.sleep();
00109 }
00110
00111 if(success)
00112 {
00113 result.set_sequence_vec(sequence);
00114 ROS_INFO("%s: Succeeded", action_name_.c_str());
00115
00116 as_.setSucceeded(result);
00117 }
00118 }
00119
00120 protected:
00121
00122 ros::NodeHandle nh_;
00123 actionlib::SimpleActionServer<actionlib_tutorials::FibonacciAction> as_;
00124 std::string action_name_;
00125 int seed0_, seed1_;
00126 };
00127
00128
00129 int main(int argc, char** argv)
00130 {
00131 ros::init(argc, argv, "fibonacci");
00132
00133 try
00134 {
00135 FibonacciAction fibonacci(ros::this_node::getName());
00136 ros::spin();
00137 }
00138 catch(std::string str)
00139 {
00140 ROS_ERROR("%s",str.c_str());
00141 }
00142 return 0;
00143 }