fibonacci_server.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  **********************************************************************/
00034 
00035 /* Author: Melonee Wise */
00036 
00037 #include <ros/ros.h>
00038 #include <actionlib/server/simple_action_server.h>
00039 #include <actionlib_tutorials/FibonacciAction.h>
00040 
00041 class FibonacciAction
00042 {
00043 public:
00044     
00045   FibonacciAction(std::string name) : 
00046     as_(nh_, name, boost::bind(&FibonacciAction::executeCB, this, _1), false),
00047     action_name_(name)
00048   {
00049     //start the action server
00050     as_.start();
00051   }
00052 
00053   ~FibonacciAction(void)
00054   {
00055   }
00056 
00057   void executeCB(const actionlib_tutorials::FibonacciGoalConstPtr &goal)
00058   {
00059     // helper variables
00060     ros::Rate r(1); 
00061     bool success = true;
00062 
00063     // push_back the seeds for the fibonacci sequence
00064     feedback_.sequence.clear();
00065     feedback_.sequence.push_back(0);
00066     feedback_.sequence.push_back(1);
00067 
00068     // publish info to the console for the user
00069     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]);
00070         
00071     // start executing the action
00072     for(int i=1; i<=goal->order; i++)
00073     {        
00074       // check that preempt has not been requested by the client
00075       if (as_.isPreemptRequested() || !ros::ok())
00076       {
00077         ROS_INFO("%s: Preempted", action_name_.c_str());
00078         // set the action state to preempted
00079         as_.setPreempted();
00080         success = false;
00081         break;
00082       }
00083       feedback_.sequence.push_back(feedback_.sequence[i] + feedback_.sequence[i-1]);
00084       // publish the feedback 
00085       as_.publishFeedback(feedback_);
00086       // this sleep is not necessary
00087       r.sleep(); 
00088     }
00089 
00090     if(success)
00091     {
00092       result_.sequence = feedback_.sequence;
00093       ROS_INFO("%s: Succeeded", action_name_.c_str());
00094       // set the action state to succeeded
00095       as_.setSucceeded(result_);
00096     }
00097   }
00098 
00099 protected:
00100     
00101   ros::NodeHandle nh_;
00102   actionlib::SimpleActionServer<actionlib_tutorials::FibonacciAction> as_;
00103   std::string action_name_;
00104   // create messages that are used to published feedback/result
00105   actionlib_tutorials::FibonacciFeedback feedback_;
00106   actionlib_tutorials::FibonacciResult result_;
00107 };
00108 
00109 
00110 int main(int argc, char** argv)
00111 {
00112   ros::init(argc, argv, "fibonacci");
00113 
00114   FibonacciAction fibonacci(ros::this_node::getName());
00115   ros::spin();
00116 
00117   return 0;
00118 }


actionlib_tutorials
Author(s): Melonee Wise
autogenerated on Thu Jan 2 2014 11:09:44