Go to the documentation of this file.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, false),
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 as_.start();
00059 }
00060
00061 ~AveragingAction(void)
00062 {
00063 }
00064
00065 void goalCB()
00066 {
00067
00068 data_count_ = 0;
00069 sum_ = 0;
00070 sum_sq_ = 0;
00071
00072 goal_ = (*as_.acceptNewGoal()).samples;
00073 }
00074
00075 void preemptCB()
00076 {
00077 ROS_INFO("%s: Preempted", action_name_.c_str());
00078
00079 as_.setPreempted();
00080 }
00081
00082 void analysisCB(const std_msgs::Float32::ConstPtr& msg)
00083 {
00084
00085 if (!as_.isActive())
00086 return;
00087
00088 data_count_++;
00089 feedback_.sample = data_count_;
00090 feedback_.data = msg->data;
00091
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
00107 as_.setAborted(result_);
00108 }
00109 else
00110 {
00111 ROS_INFO("%s: Succeeded", action_name_.c_str());
00112
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 }