averaging_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 <std_msgs/Float32.h>
00039 #include <actionlib/server/simple_action_server.h>
00040 #include <actionlib_tutorials/AveragingAction.h>
00041 
00042 class AveragingAction
00043 {
00044 public:
00045     
00046   AveragingAction(std::string name) : 
00047     as_(nh_, name, false),
00048     action_name_(name)
00049   {
00050     //register the goal and feeback callbacks
00051     as_.registerGoalCallback(boost::bind(&AveragingAction::goalCB, this));
00052     as_.registerPreemptCallback(boost::bind(&AveragingAction::preemptCB, this));
00053 
00054     //subscribe to the data topic of interest
00055     sub_ = nh_.subscribe("/random_number", 1, &AveragingAction::analysisCB, this);
00056 
00057     //start the action server
00058     as_.start();
00059   }
00060 
00061   ~AveragingAction(void)
00062   {
00063   }
00064 
00065   void goalCB()
00066   {
00067     // reset helper variables
00068     data_count_ = 0;
00069     sum_ = 0;
00070     sum_sq_ = 0;
00071     // accept the new goal
00072     goal_ = (*as_.acceptNewGoal()).samples;
00073   }
00074 
00075   void preemptCB()
00076   {
00077     ROS_INFO("%s: Preempted", action_name_.c_str());
00078     // set the action state to preempted
00079     as_.setPreempted();
00080   }
00081 
00082   void analysisCB(const std_msgs::Float32::ConstPtr& msg)
00083   {
00084     // make sure that the action hasn't been canceled
00085     if (!as_.isActive())
00086       return;
00087     
00088     data_count_++;
00089     feedback_.sample = data_count_;
00090     feedback_.data = msg->data;
00091     //compute the std_dev and mean of the data 
00092     sum_ += msg->data;
00093     feedback_.mean = sum_ / data_count_;
00094     sum_sq_ += pow(msg->data, 2);
00095     feedback_.std_dev = sqrt(fabs((sum_sq_/data_count_) - pow(feedback_.mean, 2)));
00096     as_.publishFeedback(feedback_);
00097 
00098     if(data_count_ > goal_) 
00099     {
00100       result_.mean = feedback_.mean;
00101       result_.std_dev = feedback_.std_dev;
00102 
00103       if(result_.mean < 5.0)
00104       {
00105         ROS_INFO("%s: Aborted", action_name_.c_str());
00106         //set the action state to aborted
00107         as_.setAborted(result_);
00108       }
00109       else 
00110       {
00111         ROS_INFO("%s: Succeeded", action_name_.c_str());
00112         // set the action state to succeeded
00113         as_.setSucceeded(result_);
00114       }
00115     } 
00116   }
00117 
00118 protected:
00119     
00120   ros::NodeHandle nh_;
00121   actionlib::SimpleActionServer<actionlib_tutorials::AveragingAction> as_;
00122   std::string action_name_;
00123   int data_count_, goal_;
00124   float sum_, sum_sq_;
00125   actionlib_tutorials::AveragingFeedback feedback_;
00126   actionlib_tutorials::AveragingResult result_;
00127   ros::Subscriber sub_;
00128 };
00129 
00130 int main(int argc, char** argv)
00131 {
00132   ros::init(argc, argv, "averaging");
00133 
00134   AveragingAction averaging(ros::this_node::getName());
00135   ros::spin();
00136 
00137   return 0;
00138 }


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