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