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
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
00051 as_.registerGoalCallback(boost::bind(&AveragingAction::goalCB, this));
00052 as_.registerPreemptCallback(boost::bind(&AveragingAction::preemptCB, this));
00053
00054
00055 sub_ = nh_.subscribe("/random_number", 1, &AveragingAction::analysisCB, this);
00056 }
00057
00058 ~AveragingAction(void)
00059 {
00060 }
00061
00062 void goalCB()
00063 {
00064
00065 data_count_ = 0;
00066 sum_ = 0;
00067 sum_sq_ = 0;
00068
00069 goal_ = (*as_.acceptNewGoal()).samples;
00070 }
00071
00072 void preemptCB()
00073 {
00074 ROS_INFO("%s: Preempted", action_name_.c_str());
00075
00076 as_.setPreempted();
00077 }
00078
00079 void analysisCB(const std_msgs::Float32::ConstPtr& msg)
00080 {
00081
00082 if (!as_.isActive())
00083 return;
00084
00085 data_count_++;
00086 feedback_.sample = data_count_;
00087 feedback_.data = msg->data;
00088
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
00104 as_.setAborted(result_);
00105 }
00106 else
00107 {
00108 ROS_INFO("%s: Succeeded", action_name_.c_str());
00109
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 }