averaging_client.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
4 #include <actionlib_tutorials/AveragingAction.h>
5 #include <boost/thread.hpp>
6 
7 void spinThread()
8 {
9  ros::spin();
10 }
11 
12 int main (int argc, char **argv)
13 {
14  ros::init(argc, argv, "test_averaging");
15 
16  // create the action client
18  boost::thread spin_thread(&spinThread);
19 
20  ROS_INFO("Waiting for action server to start.");
21  ac.waitForServer();
22 
23  ROS_INFO("Action server started, sending goal.");
24  // send a goal to the action
25  actionlib_tutorials::AveragingGoal goal;
26  goal.samples = 100;
27  ac.sendGoal(goal);
28 
29  //wait for the action to return
30  bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));
31 
32  if (finished_before_timeout)
33  {
35  ROS_INFO("Action finished: %s",state.toString().c_str());
36  }
37  else
38  ROS_INFO("Action did not finish before the time out.");
39 
40  // shutdown the node and join the thread back before exiting
41  ros::shutdown();
42  spin_thread.join();
43 
44  //exit
45  return 0;
46 }
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
int main(int argc, char **argv)
#define ROS_INFO(...)
void spinThread()
ROSCPP_DECL void spin()
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
ROSCPP_DECL void shutdown()
SimpleClientGoalState getState() const


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