shape_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 <turtle_actionlib/ShapeAction.h>
00005 
00006 int main (int argc, char **argv)
00007 {
00008   ros::init(argc, argv, "test_shape"); 
00009 
00010   // create the action client
00011   // true causes the client to spin it's own thread
00012   actionlib::SimpleActionClient<turtle_actionlib::ShapeAction> ac("turtle_shape", 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   turtle_actionlib::ShapeGoal goal;
00021   goal.edges = 5;
00022   goal.radius = 1.3;
00023   ac.sendGoal(goal);
00024   
00025   //wait for the action to return
00026   bool finished_before_timeout = ac.waitForResult(ros::Duration(40.0));
00027 
00028   if (finished_before_timeout)
00029     {
00030       actionlib::SimpleClientGoalState state = ac.getState();
00031       ROS_INFO("Action finished: %s",state.toString().c_str());
00032     }
00033   else  
00034     ROS_INFO("Action did not finish before the time out.");
00035 
00036   //exit
00037   return 0;
00038 }


turtle_actionlib
Author(s): Melonee Wise
autogenerated on Thu Jan 2 2014 11:09:58