fibonacci_class_client.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <actionlib/client/simple_action_client.h>
00003 #include <actionlib_tutorials/FibonacciAction.h>
00004 
00005 using namespace actionlib_tutorials;
00006 typedef actionlib::SimpleActionClient<FibonacciAction> Client;
00007 
00008 class MyNode
00009 {
00010 public:
00011   MyNode() : ac("fibonacci", true)
00012   {
00013     ROS_INFO("Waiting for action server to start.");
00014     ac.waitForServer();
00015     ROS_INFO("Action server started, sending goal.");
00016   }
00017 
00018   void doStuff(int order)
00019   {
00020     FibonacciGoal goal;
00021     goal.order = order;
00022 
00023     // Need boost::bind to pass in the 'this' pointer
00024     ac.sendGoal(goal,
00025                 boost::bind(&MyNode::doneCb, this, _1, _2),
00026                 Client::SimpleActiveCallback(),
00027                 Client::SimpleFeedbackCallback());
00028 
00029   }
00030 
00031   void doneCb(const actionlib::SimpleClientGoalState& state,
00032               const FibonacciResultConstPtr& result)
00033   {
00034     ROS_INFO("Finished in state [%s]", state.toString().c_str());
00035     ROS_INFO("Answer: %i", result->sequence.back());
00036     ros::shutdown();
00037   }
00038 
00039 private:
00040   Client ac;
00041 };
00042 
00043 int main (int argc, char **argv)
00044 {
00045   ros::init(argc, argv, "test_fibonacci_class_client");
00046   MyNode my_node;
00047   my_node.doStuff(10);
00048   ros::spin();
00049   return 0;
00050 }


actionlib_tutorials
Author(s): Melonee Wise
autogenerated on Thu Jun 6 2019 21:11:25