fibonacci_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/client/terminal_state.h>
00004 #include <actionlib_tutorials/FibonacciAction.h>
00005 
00006 int main (int argc, char **argv)
00007 {
00008   ros::init(argc, argv, "test_fibonacci");
00009 
00010   // create the action client
00011   // true causes the client to spin its own thread
00012   actionlib::SimpleActionClient<actionlib_tutorials::FibonacciAction> ac("fibonacci", true);
00013 
00014   ROS_INFO("Waiting for action server to start.");
00015   // wait for the action server to start
00016   ac.waitForServer(); //will wait for infinite time
00017 
00018   ROS_INFO("Action server started, sending goal.");
00019   // send a goal to the action
00020   actionlib_tutorials::FibonacciGoal goal;
00021   goal.order = 20;
00022   ac.sendGoal(goal);
00023 
00024   //wait for the action to return
00025   bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));
00026 
00027   if (finished_before_timeout)
00028   {
00029     actionlib::SimpleClientGoalState state = ac.getState();
00030     ROS_INFO("Action finished: %s",state.toString().c_str());
00031   }
00032   else
00033     ROS_INFO("Action did not finish before the time out.");
00034 
00035   //exit
00036   return 0;
00037 }


actionlib_tutorials
Author(s): Melonee Wise
autogenerated on Sun Oct 5 2014 23:14:55