2 #include <std_msgs/Float32.h> 4 #include <actionlib_tutorials/AveragingAction.h> 88 actionlib_tutorials::AveragingResult
result_;
92 int main(
int argc,
char** argv)
boost::shared_ptr< const Goal > acceptNewGoal()
void publishFeedback(const FeedbackConstPtr &feedback)
void analysisCB(const std_msgs::Float32::ConstPtr &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL const std::string & getName()
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
actionlib_tutorials::AveragingResult result_
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
actionlib_tutorials::AveragingFeedback feedback_
void registerPreemptCallback(boost::function< void()> cb)
AveragingAction(std::string name)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
int main(int argc, char **argv)
actionlib::SimpleActionServer< actionlib_tutorials::AveragingAction > as_
void registerGoalCallback(boost::function< void()> cb)