fibonacci_client.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
4 #include <actionlib_tutorials/FibonacciAction.h>
5 
6 int main (int argc, char **argv)
7 {
8  ros::init(argc, argv, "test_fibonacci");
9 
10  // create the action client
11  // true causes the client to spin its 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  actionlib_tutorials::FibonacciGoal goal;
21  goal.order = 20;
22  ac.sendGoal(goal);
23 
24  //wait for the action to return
25  bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));
26 
27  if (finished_before_timeout)
28  {
30  ROS_INFO("Action finished: %s",state.toString().c_str());
31  }
32  else
33  ROS_INFO("Action did not finish before the time out.");
34 
35  //exit
36  return 0;
37 }
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)
std::string toString() const
#define ROS_INFO(...)
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
int main(int argc, char **argv)
SimpleClientGoalState getState() const


actionlib_tutorials
Author(s): Melonee Wise
autogenerated on Wed Jun 5 2019 20:54:23