shape_client.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
4 #include <turtle_actionlib/ShapeAction.h>
5 
6 int main (int argc, char **argv)
7 {
8  ros::init(argc, argv, "test_shape");
9 
10  // create the action client
11  // true causes the client to spin it's own thread
13 
14  ROS_INFO("Waiting for action server to start.");
15  // wait for the action server to start
16  ac.waitForServer(); //will wait for infinite time
17 
18  ROS_INFO("Action server started, sending goal.");
19  // send a goal to the action
20  turtle_actionlib::ShapeGoal goal;
21  goal.edges = 5;
22  goal.radius = 1.3;
23  ac.sendGoal(goal);
24 
25  //wait for the action to return
26  bool finished_before_timeout = ac.waitForResult(ros::Duration(40.0));
27 
28  if (finished_before_timeout)
29  {
31  ROS_INFO("Action finished: %s",state.toString().c_str());
32  }
33  else
34  ROS_INFO("Action did not finish before the time out.");
35 
36  //exit
37  return 0;
38 }
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
Definition: shape_client.cpp:6
std::string toString() const
#define ROS_INFO(...)
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
SimpleClientGoalState getState() const


turtle_actionlib
Author(s): Melonee Wise
autogenerated on Wed Jun 5 2019 20:54:28